From bffd5b0b53d9929f68ce2dcbfad2b425fa56db46 Mon Sep 17 00:00:00 2001 From: Roni Kant <35043400+Penguronik@users.noreply.github.com> Date: Wed, 7 Feb 2024 12:48:15 -0500 Subject: [PATCH 01/15] Added OutputToMotor method (#31) Co-authored-by: Aidan Bowers Co-authored-by: Anthony Bertnyk Co-authored-by: Anthony Luo Co-authored-by: DerekTang04 Co-authored-by: Derek Tang <68519418+DerekTang04@users.noreply.github.com> --- AttitudeManager/Inc/AM.hpp | 29 +- AttitudeManager/Src/AM.cpp | 24 +- AttitudeManager/Tests/AMTest.cpp | 278 ++++++++++++++++++ .../config_foundation.hpp | 3 +- .../example_model/config.hpp | 1 + {Models => Config_Models}/temp.txt | 0 {Models => Config_Models}/temp_drivers.hpp | 10 +- Testing/Mocks/Inc/MockChannel.hpp | 14 + Testing/Mocks/Inc/MockFlightmode.hpp | 8 + Testing/Mocks/Src/MockChannel.cpp | 4 + Testing/Stubs/Inc/FreeRTOS.h | 8 + Testing/Stubs/Inc/semphr.h | 9 + Testing/Stubs/Src/semphr.cpp | 2 + Tools/Firmware/CMakeLists.txt | 4 + Tools/Testing/CMakeLists.txt | 65 +++- 15 files changed, 439 insertions(+), 20 deletions(-) create mode 100644 AttitudeManager/Tests/AMTest.cpp rename {Models => Config_Models}/config_foundation.hpp (98%) rename {Models => Config_Models}/example_model/config.hpp (99%) rename {Models => Config_Models}/temp.txt (100%) rename {Models => Config_Models}/temp_drivers.hpp (86%) create mode 100644 Testing/Mocks/Inc/MockChannel.hpp create mode 100644 Testing/Mocks/Inc/MockFlightmode.hpp create mode 100644 Testing/Mocks/Src/MockChannel.cpp create mode 100644 Testing/Stubs/Inc/FreeRTOS.h create mode 100644 Testing/Stubs/Inc/semphr.h create mode 100644 Testing/Stubs/Src/semphr.cpp diff --git a/AttitudeManager/Inc/AM.hpp b/AttitudeManager/Inc/AM.hpp index 1bc70836..6b9a780c 100644 --- a/AttitudeManager/Inc/AM.hpp +++ b/AttitudeManager/Inc/AM.hpp @@ -11,30 +11,53 @@ #include "AM_ControlAlgorithm.hpp" #include "CommonDataTypes.hpp" - +#include "config_foundation.hpp" #include "FreeRTOS.h" #include "semphr.h" +#ifdef TESTING +#include +#endif namespace AM { +typedef struct { + MotorChannel *motorInstance; + bool isInverted; + } MotorInstance_t; + class AttitudeManager { public: static void setControlInputs(const AttitudeManagerInput& new_control_inputs); static AttitudeManagerInput getControlInputs(); - AttitudeManager(Flightmode* control_algorithm) : control_algorithm(control_algorithm){}; + AttitudeManager(Flightmode* controlAlgorithm, MotorInstance_t *(&motorInstances)[], uint8_t (&numMotorsPerAxis)[]); + + ~AttitudeManager(); void runControlLoopIteration(const AttitudeManagerInput& instructions); private: + #ifdef TESTING + FRIEND_TEST(AttitudeManager, MotorInitializationAndOutput); // Remove FRIEND_TEST when updating tests with setControlInputs + FRIEND_TEST(AttitudeManagerOutputToMotor, NoMotors); + FRIEND_TEST(AttitudeManagerOutputToMotor, MotorsOfSameAxis); + FRIEND_TEST(AttitudeManagerOutputToMotor, setOutputInRandomAxisOrder); + FRIEND_TEST(AttitudeManagerOutputToMotor, InvertedTest); + FRIEND_TEST(AttitudeManagerOutputToMotor, CombinedTest); + #endif + AttitudeManager(); + void outputToMotor(config::ControlAxis_t axis, uint8_t percent); static SemaphoreHandle_t control_inputs_mutex; static struct AttitudeManagerInput control_inputs; - Flightmode* control_algorithm; + Flightmode *controlAlgorithm_; + MotorInstance_t *(&motorInstances_)[]; + uint8_t (&numMotorsPerAxis_)[]; + }; } // namespace AM diff --git a/AttitudeManager/Src/AM.cpp b/AttitudeManager/Src/AM.cpp index e68556fc..7baafcb9 100644 --- a/AttitudeManager/Src/AM.cpp +++ b/AttitudeManager/Src/AM.cpp @@ -35,13 +35,35 @@ AttitudeManagerInput AttitudeManager::getControlInputs() { return temp; } +AttitudeManager::AttitudeManager(Flightmode* controlAlgorithm, MotorInstance_t *(&motorInstances)[], uint8_t (&numMotorsPerAxis)[]): + controlAlgorithm_(controlAlgorithm), + motorInstances_(motorInstances), + numMotorsPerAxis_(numMotorsPerAxis) +{}; + +AttitudeManager::~AttitudeManager() +{} + void AttitudeManager::runControlLoopIteration(const AttitudeManagerInput& instructions) { // Process Instructions // Run Control Algorithms - control_algorithm->run(); + controlAlgorithm_->run(); // Write motor outputs } +void AttitudeManager::outputToMotor(config::ControlAxis_t axis, uint8_t percent) { + // Move through the portion of the motorInstances array that matches the wanted axis. + // The motorReferences array holds references to the wanted positions in the motorInstances array + for (uint8_t motorCount{0}; motorCount < numMotorsPerAxis_[axis]; ++motorCount) { + if (motorInstances_[axis][motorCount].isInverted) { + motorInstances_[axis][motorCount].motorInstance->set(100-percent); + } else { + motorInstances_[axis][motorCount].motorInstance->set(percent); + } + } + +} + } // namespace AM diff --git a/AttitudeManager/Tests/AMTest.cpp b/AttitudeManager/Tests/AMTest.cpp new file mode 100644 index 00000000..5a331417 --- /dev/null +++ b/AttitudeManager/Tests/AMTest.cpp @@ -0,0 +1,278 @@ +#include +#include +#include "AM.hpp" +#include "config_foundation.hpp" +#include "MockChannel.hpp" +#include "MockFlightmode.hpp" + +namespace AM { + +TEST(AttitudeManagerOutputToMotor, NoMotors) { + MockFlightmode controlAlgorithm{}; + MotorInstance_t *motorInstances[config::NUM_CONTROL_AXIS]{nullptr}; + uint8_t numMotorsPerAxis[config::NUM_CONTROL_AXIS]{0}; + + AM::AttitudeManager am{&controlAlgorithm, motorInstances, numMotorsPerAxis}; + + am.outputToMotor(config::throttle, 40); + am.outputToMotor(config::pitch, 30); + am.outputToMotor(config::roll, 20); + am.outputToMotor(config::yaw, 10); +} + +TEST(AttitudeManagerOutputToMotor, MotorsOfSameAxis) { + MockFlightmode controlAlgorithm{}; + MotorInstance_t *motorInstances[config::NUM_CONTROL_AXIS]{nullptr}; + uint8_t numMotorsPerAxis[config::NUM_CONTROL_AXIS]{0}; + + MockChannel mockChannelReferences[5]{}; + + MotorInstance_t pitchMotorReferences[] = { + { + .motorInstance = &mockChannelReferences[0], + .isInverted = false + }, + { + .motorInstance = &mockChannelReferences[1], + .isInverted = false + }, + { + .motorInstance = &mockChannelReferences[2], + .isInverted = false + }, + { + .motorInstance = &mockChannelReferences[3], + .isInverted = false + }, + { + .motorInstance = &mockChannelReferences[4], + .isInverted = false + } + }; + + motorInstances[config::pitch] = pitchMotorReferences; + + numMotorsPerAxis[config::pitch] = 5; + + AM::AttitudeManager am{&controlAlgorithm, motorInstances, numMotorsPerAxis}; + + // Setting non-existent motors shouldn't affect yaw + EXPECT_CALL(mockChannelReferences[0], set(30)); + EXPECT_CALL(mockChannelReferences[1], set(30)); + EXPECT_CALL(mockChannelReferences[2], set(30)); + EXPECT_CALL(mockChannelReferences[3], set(30)); + EXPECT_CALL(mockChannelReferences[4], set(30)); + + am.outputToMotor(config::yaw, 10); + am.outputToMotor(config::throttle, 40); + am.outputToMotor(config::pitch, 30); + am.outputToMotor(config::roll, 20); + + // Should set all of them + EXPECT_CALL(mockChannelReferences[0], set(60)); + EXPECT_CALL(mockChannelReferences[1], set(60)); + EXPECT_CALL(mockChannelReferences[2], set(60)); + EXPECT_CALL(mockChannelReferences[3], set(60)); + EXPECT_CALL(mockChannelReferences[4], set(60)); + + am.outputToMotor(config::pitch, 60); +} + +TEST(AttitudeManagerOutputToMotor, setOutputInRandomAxisOrder) { + MockFlightmode controlAlgorithm{}; + MotorInstance_t *motorInstances[config::NUM_CONTROL_AXIS]{nullptr}; + uint8_t numMotorsPerAxis[config::NUM_CONTROL_AXIS]{0}; + + MockChannel mockChannelReferences[4]{}; + + MotorInstance_t yawMotorReferences[] = { + { + .motorInstance = &mockChannelReferences[0], + .isInverted = false + } + }; + + MotorInstance_t pitchMotorReferences[] = { + { + .motorInstance = &mockChannelReferences[1], + .isInverted = false + } + }; + + MotorInstance_t rollMotorReferences[] = { + { + .motorInstance = &mockChannelReferences[2], + .isInverted = false + } + }; + + MotorInstance_t throttleMotorReferences[] = { + { + .motorInstance = &mockChannelReferences[3], + .isInverted = false + } + }; + + motorInstances[config::yaw] = yawMotorReferences; + motorInstances[config::pitch] = pitchMotorReferences; + motorInstances[config::roll] = rollMotorReferences; + motorInstances[config::throttle] = throttleMotorReferences; + + numMotorsPerAxis[config::yaw] = 1; + numMotorsPerAxis[config::pitch] = 1; + numMotorsPerAxis[config::roll] = 1; + numMotorsPerAxis[config::throttle] = 1; + + AM::AttitudeManager am{&controlAlgorithm, motorInstances, numMotorsPerAxis}; + + // Should invert all inputs + EXPECT_CALL(mockChannelReferences[0], set(12)); + EXPECT_CALL(mockChannelReferences[1], set(75)); + EXPECT_CALL(mockChannelReferences[2], set(100)); + EXPECT_CALL(mockChannelReferences[3], set(33)); + + am.outputToMotor(config::yaw, 12); + am.outputToMotor(config::throttle, 33); + am.outputToMotor(config::pitch, 75); + am.outputToMotor(config::roll, 100); +} + +TEST(AttitudeManagerOutputToMotor, InvertedTest) { + MockFlightmode controlAlgorithm{}; + MotorInstance_t *motorInstances[config::NUM_CONTROL_AXIS]{nullptr}; + uint8_t numMotorsPerAxis[config::NUM_CONTROL_AXIS]{0}; + + MockChannel mockChannelReferences[4]{}; + + MotorInstance_t yawMotorReferences[] = { + { + .motorInstance = &mockChannelReferences[0], + .isInverted = true + } + }; + + MotorInstance_t pitchMotorReferences[] = { + { + .motorInstance = &mockChannelReferences[1], + .isInverted = true + } + }; + + MotorInstance_t rollMotorReferences[] = { + { + .motorInstance = &mockChannelReferences[2], + .isInverted = true + } + }; + + MotorInstance_t throttleMotorReferences[] = { + { + .motorInstance = &mockChannelReferences[3], + .isInverted = true + } + }; + + motorInstances[config::yaw] = yawMotorReferences; + motorInstances[config::pitch] = pitchMotorReferences; + motorInstances[config::roll] = rollMotorReferences; + motorInstances[config::throttle] = throttleMotorReferences; + + numMotorsPerAxis[config::yaw] = 1; + numMotorsPerAxis[config::pitch] = 1; + numMotorsPerAxis[config::roll] = 1; + numMotorsPerAxis[config::throttle] = 1; + + AM::AttitudeManager am{&controlAlgorithm, motorInstances, numMotorsPerAxis}; + + // Should invert all inputs + EXPECT_CALL(mockChannelReferences[0], set(88)); + EXPECT_CALL(mockChannelReferences[1], set(25)); + EXPECT_CALL(mockChannelReferences[2], set(0)); + EXPECT_CALL(mockChannelReferences[3], set(67)); + + am.outputToMotor(config::yaw, 12); + am.outputToMotor(config::pitch, 75); + am.outputToMotor(config::roll, 100); + am.outputToMotor(config::throttle, 33); +} + +TEST(AttitudeManagerOutputToMotor, CombinedTest) { + MockFlightmode controlAlgorithm{}; + MotorInstance_t *motorInstances[config::NUM_CONTROL_AXIS]{nullptr}; + uint8_t numMotorsPerAxis[config::NUM_CONTROL_AXIS]{0}; + + MockChannel mockChannelReferences[8]{}; + + MotorInstance_t yawMotorReferences[] = { + { + .motorInstance = &mockChannelReferences[0], + .isInverted = false + }, + { + .motorInstance = &mockChannelReferences[1], + .isInverted = false + } + }; + + MotorInstance_t pitchMotorReferences[] = { + { + .motorInstance = &mockChannelReferences[2], + .isInverted = true + }, + { + .motorInstance = &mockChannelReferences[3], + .isInverted = true + }, + { + .motorInstance = &mockChannelReferences[4], + .isInverted = false + } + }; + + MotorInstance_t rollMotorReferences[] = { + { + .motorInstance = &mockChannelReferences[5], + .isInverted = false + } + }; + + MotorInstance_t throttleMotorReferences[] = { + { + .motorInstance = &mockChannelReferences[6], + .isInverted = false + }, + { + .motorInstance = &mockChannelReferences[7], + .isInverted = true + } + }; + + motorInstances[config::yaw] = yawMotorReferences; + motorInstances[config::pitch] = pitchMotorReferences; + motorInstances[config::roll] = rollMotorReferences; + motorInstances[config::throttle] = throttleMotorReferences; + + numMotorsPerAxis[config::yaw] = 2; + numMotorsPerAxis[config::pitch] = 3; + numMotorsPerAxis[config::roll] = 1; + numMotorsPerAxis[config::throttle] = 2; + + AM::AttitudeManager am{&controlAlgorithm, motorInstances, numMotorsPerAxis}; + + // Should invert all necessary inputs + EXPECT_CALL(mockChannelReferences[0], set(84)); + EXPECT_CALL(mockChannelReferences[1], set(84)); + EXPECT_CALL(mockChannelReferences[2], set(73)); + EXPECT_CALL(mockChannelReferences[3], set(73)); + EXPECT_CALL(mockChannelReferences[4], set(27)); + EXPECT_CALL(mockChannelReferences[5], set(94)); + EXPECT_CALL(mockChannelReferences[6], set(5)); + EXPECT_CALL(mockChannelReferences[7], set(95)); + + am.outputToMotor(config::yaw, 84); + am.outputToMotor(config::pitch, 27); + am.outputToMotor(config::roll, 94); + am.outputToMotor(config::throttle, 5); +} + +} \ No newline at end of file diff --git a/Models/config_foundation.hpp b/Config_Models/config_foundation.hpp similarity index 98% rename from Models/config_foundation.hpp rename to Config_Models/config_foundation.hpp index 15832ce5..461840f6 100644 --- a/Models/config_foundation.hpp +++ b/Config_Models/config_foundation.hpp @@ -28,7 +28,8 @@ namespace config yaw, pitch, roll, - throttle + throttle, + NUM_CONTROL_AXIS } ControlAxis_t; typedef struct { diff --git a/Models/example_model/config.hpp b/Config_Models/example_model/config.hpp similarity index 99% rename from Models/example_model/config.hpp rename to Config_Models/example_model/config.hpp index 27d420be..ccb7e895 100644 --- a/Models/example_model/config.hpp +++ b/Config_Models/example_model/config.hpp @@ -2,6 +2,7 @@ #define ZPSW3_CONFIG_HPP #include "config_foundation.hpp" +#include "ZP_D_PWMChannel.hpp" #include "tim.h" namespace config diff --git a/Models/temp.txt b/Config_Models/temp.txt similarity index 100% rename from Models/temp.txt rename to Config_Models/temp.txt diff --git a/Models/temp_drivers.hpp b/Config_Models/temp_drivers.hpp similarity index 86% rename from Models/temp_drivers.hpp rename to Config_Models/temp_drivers.hpp index dfb4cdae..130df1ee 100644 --- a/Models/temp_drivers.hpp +++ b/Config_Models/temp_drivers.hpp @@ -3,7 +3,7 @@ //TODO: Remove this file when drivers and flightmodes are implemented -#include "ZP_D_PWMChannel.hpp" +#include "ZP_D_MotorChannel.hpp" class TempDSHOTDriver : public MotorChannel { @@ -22,15 +22,15 @@ class ExampleFlightmode1 : public AM::Flightmode{ public: ExampleFlightmode1(){} //TODO: Implement control algorithm functions in AM - void run(); - void updatePid(); + void run(){}; + void updatePid(){}; }; class ExampleFlightmode2 : public AM::Flightmode{ public: ExampleFlightmode2(){} - void run(); - void updatePid(); + void run(){}; + void updatePid(){}; }; diff --git a/Testing/Mocks/Inc/MockChannel.hpp b/Testing/Mocks/Inc/MockChannel.hpp new file mode 100644 index 00000000..a9d8e7c3 --- /dev/null +++ b/Testing/Mocks/Inc/MockChannel.hpp @@ -0,0 +1,14 @@ +#ifndef ZP_D_MOCK_CHANNEL_HPP_ +#define ZP_D_MOCK_CHANNEL_HPP_ + +#include "ZP_D_MotorChannel.hpp" +#include + +class MockChannel : public MotorChannel { + public: + MockChannel(); + + MOCK_METHOD(void, set, (uint8_t)); +}; + +#endif // ZP_D_PWM_CHANNEL_HPP_ diff --git a/Testing/Mocks/Inc/MockFlightmode.hpp b/Testing/Mocks/Inc/MockFlightmode.hpp new file mode 100644 index 00000000..cf87bd29 --- /dev/null +++ b/Testing/Mocks/Inc/MockFlightmode.hpp @@ -0,0 +1,8 @@ +#include "AM_ControlAlgorithm.hpp" + +class MockFlightmode : public AM::Flightmode{ + public: + MockFlightmode(){} + void run(){}; + void updatePid(){}; +}; \ No newline at end of file diff --git a/Testing/Mocks/Src/MockChannel.cpp b/Testing/Mocks/Src/MockChannel.cpp new file mode 100644 index 00000000..722dd158 --- /dev/null +++ b/Testing/Mocks/Src/MockChannel.cpp @@ -0,0 +1,4 @@ +#include "MockChannel.hpp" + +MockChannel::MockChannel() +{} \ No newline at end of file diff --git a/Testing/Stubs/Inc/FreeRTOS.h b/Testing/Stubs/Inc/FreeRTOS.h new file mode 100644 index 00000000..44594ca5 --- /dev/null +++ b/Testing/Stubs/Inc/FreeRTOS.h @@ -0,0 +1,8 @@ +#ifndef FREERTOS_H +#define FREERTOS_H + +typedef int TickType_t; +#define portMAX_DELAY 0 +#define pdPASS 1 + +#endif // FREERTOS_H \ No newline at end of file diff --git a/Testing/Stubs/Inc/semphr.h b/Testing/Stubs/Inc/semphr.h new file mode 100644 index 00000000..12a86476 --- /dev/null +++ b/Testing/Stubs/Inc/semphr.h @@ -0,0 +1,9 @@ +#ifndef SEMPHR_H +#define SEMPHR_H + +typedef int SemaphoreHandle_t; +#define xSemaphoreCreateMutex() 0 +long xSemaphoreTake(int, int); +#define xSemaphoreGive(x) ((void)x) + +#endif // SEMPHR_H \ No newline at end of file diff --git a/Testing/Stubs/Src/semphr.cpp b/Testing/Stubs/Src/semphr.cpp new file mode 100644 index 00000000..ae65d6b5 --- /dev/null +++ b/Testing/Stubs/Src/semphr.cpp @@ -0,0 +1,2 @@ +#include "semphr.h" +long xSemaphoreTake(int, int) {return 0;} \ No newline at end of file diff --git a/Tools/Firmware/CMakeLists.txt b/Tools/Firmware/CMakeLists.txt index 104425dc..2102c3a6 100644 --- a/Tools/Firmware/CMakeLists.txt +++ b/Tools/Firmware/CMakeLists.txt @@ -45,6 +45,10 @@ include_directories( ${ROOT_DIR}/Boardfiles/${FOLDER_NAME}/Middlewares/Third_Party/FreeRTOS/Source/CMSIS_RTOS_V2 ${ROOT_DIR}/Boardfiles/${FOLDER_NAME}/Middlewares/Third_Party/FreeRTOS/Source/portable/GCC/ARM_${PORTABLE_NAME} ${ROOT_DIR}/Boardfiles/${FOLDER_NAME}/Middlewares/Third_Party/FreeRTOS/Source/include + + ## Models Includes ## + ${ROOT_DIR}/Config_Models + ${ROOT_DIR}/Config_Models/${MODEL_NAME} ) ## Boardfile Sources ## diff --git a/Tools/Testing/CMakeLists.txt b/Tools/Testing/CMakeLists.txt index 1b78fd6f..1db36380 100644 --- a/Tools/Testing/CMakeLists.txt +++ b/Tools/Testing/CMakeLists.txt @@ -5,9 +5,12 @@ set(CMAKE_C_COMPILER "gcc") set(CMAKE_CXX_COMPILER "g++") # GoogleTest requires at least C++14 -set(CMAKE_CXX_STANDARD 14) +set(CMAKE_CXX_STANDARD 20) set(CMAKE_CXX_STANDARD_REQUIRED ON) +# Define TESTING Preprocessor Macro +add_compile_definitions(TESTING) + # Locate GTest find_package(GTest REQUIRED) include_directories(${GTEST_INCLUDE_DIRS}) @@ -23,21 +26,24 @@ set(ROOT_DIR "${CMAKE_CURRENT_SOURCE_DIR}/../..") # Attitude Manager set(AM_FOLDER "${ROOT_DIR}/AttitudeManager") -set(AM_INC "{$AM_FOLDER}/Inc") -set(AM_SRC "{$AM_FOLDER}/Src") +set(AM_INC "${AM_FOLDER}/Inc") +set(AM_SRC "${AM_FOLDER}/Src") +set(FLIGHTMODES_INC "${AM_FOLDER}/FlightModes/Inc") +set(FLIGHTMODES_SRC "${AM_FOLDER}/FlightModes/Src") -include_directories(${AM_INC}) +include_directories(${AM_INC} ${FLIGHTMODES_INC}) file(GLOB AM_CODE "${AM_FOLDER}/Tests/*.cpp" # add necessary AttitudeManager source files below - # "${AM_SRC}/foo.cpp" + "${AM_SRC}/*.cpp" + "${FLIGHTMODES_SRC}/*.cpp" ) # Path Manager set(PM_FOLDER "${ROOT_DIR}/PathManager") -set(PM_INC "{$PM_FOLDER}/Inc") -set(PM_SRC "{$PM_FOLDER}/Src") +set(PM_INC "${PM_FOLDER}/Inc") +set(PM_SRC "${PM_FOLDER}/Src") include_directories(${PM_INC}) file(GLOB PM_CODE @@ -49,8 +55,8 @@ file(GLOB PM_CODE # System Manager set(SM_FOLDER "${ROOT_DIR}/SystemManager") -set(SM_INC "{$SM_FOLDER}/Inc") -set(SM_SRC "{$SM_FOLDER}/Src") +set(SM_INC "${SM_FOLDER}/Inc") +set(SM_SRC "${SM_FOLDER}/Src") include_directories(${SM_INC}) file(GLOB SM_CODE @@ -77,14 +83,50 @@ file(GLOB TM_CODE set(DRIVERS_FOLDER "${ROOT_DIR}/Drivers") set(DRIVERS_INC "${DRIVERS_FOLDER}/Common/Inc") set(DRIVERS_SRC "{$DRIVERS_FOLDER}/Src") +set(MOTORCHANNEL_INC "${DRIVERS_FOLDER}/MotorChannel/Inc") +set(MOTORCHANNEL_SRC "${DRIVERS_FOLDER}/MotorChannel/Src") +# Driver Mocks +set(MOTORCHANNEL_MOCK_INC "${ROOT_DIR}/Testing/Mocks/Inc") +set(MOTORCHANNEL_MOCK_SRC "${ROOT_DIR}/Testing/Mocks/Src") -include_directories(${DRIVERS_INC}) +include_directories(${DRIVERS_INC} ${MOTORCHANNEL_INC} ${MOTORCHANNEL_MOCK_INC}) file(GLOB DRIVERS_CODE "${DRIVERS_FOLDER}/Tests/*.cpp" # add necessary Drivers source files below # "${DRIVERS_SRC}/foo.cpp" "${DRIVERS_FOLDER}/Common/Src/circular_buffer.cpp" + "${MOTORCHANNEL_MOCK_SRC}/*.cpp" +) + +# Common +set(COMMON_FOLDER "${ROOT_DIR}/Common") +set(COMMON_INC "${COMMON_FOLDER}/Inc") +set(COMMON_SRC "${COMMON_FOLDER}/Src") + +include_directories(${COMMON_INC}) +file(GLOB COMMON_CODE + "${COMMON_FOLDER}/Tests/*.cpp" + + # add necessary TelemetryManager source files below + # "${COMMON_SRC}/foo.cpp" +) + + +# Testing stubs +set(STUBS_FOLDER "${ROOT_DIR}/Testing/Stubs") +set(STUBS_INC "${STUBS_FOLDER}/Inc") +set(STUBS_SRC "${STUBS_FOLDER}/Src") + +include_directories(${STUBS_INC}) +file(GLOB STUBS_CODE + "${STUBS_SRC}/*.cpp" + "${STUBS_SRC}/*.c" +) + +#Models +include_directories("${ROOT_DIR}/Config_Models") +file(GLOB MODELS_CODE ) # --- ZeroPilot File Indexing End --- @@ -95,6 +137,9 @@ add_executable(${PROJECT_NAME} ${SM_CODE} ${TM_CODE} ${DRIVERS_CODE} + ${COMMON_CODE} + ${STUBS_CODE} + ${MODELS_CODE} ) target_link_libraries(${PROJECT_NAME} From 9bb7d7eb96e77504c79fbeac30d47b45cd89e134 Mon Sep 17 00:00:00 2001 From: Aidan Bowers Date: Sun, 17 Mar 2024 22:58:57 -0400 Subject: [PATCH 02/15] Am/input mapping (#28) --- ...AM_ControlAlgorithm.hpp => flightmode.hpp} | 11 +- AttitudeManager/FlightModes/Inc/manual.hpp | 18 ++ AttitudeManager/FlightModes/Src/manual.cpp | 12 ++ AttitudeManager/Inc/AM.hpp | 15 +- AttitudeManager/Src/AM.cpp | 16 +- AttitudeManager/Tests/AMTest.cpp | 180 ++++++++++++------ AttitudeManager/Tests/ExampleTest.cpp | 9 - AttitudeManager/Tests/ManualControlTest.cpp | 29 +++ Common/Inc/CommonDataTypes.hpp | 7 + Common/Inc/constrain.h | 2 +- Config_Models/config_foundation.hpp | 16 +- Config_Models/example_model/config.hpp | 9 +- Config_Models/temp_drivers.hpp | 16 -- Testing/Mocks/Inc/MockFlightmode.hpp | 8 +- Testing/Stubs/Src/semphr.cpp | 2 +- Tools/Testing/CMakeLists.txt | 4 +- 16 files changed, 230 insertions(+), 124 deletions(-) rename AttitudeManager/FlightModes/Inc/{AM_ControlAlgorithm.hpp => flightmode.hpp} (72%) create mode 100644 AttitudeManager/FlightModes/Inc/manual.hpp create mode 100644 AttitudeManager/FlightModes/Src/manual.cpp delete mode 100644 AttitudeManager/Tests/ExampleTest.cpp create mode 100644 AttitudeManager/Tests/ManualControlTest.cpp diff --git a/AttitudeManager/FlightModes/Inc/AM_ControlAlgorithm.hpp b/AttitudeManager/FlightModes/Inc/flightmode.hpp similarity index 72% rename from AttitudeManager/FlightModes/Inc/AM_ControlAlgorithm.hpp rename to AttitudeManager/FlightModes/Inc/flightmode.hpp index 87ba2443..f62902d8 100644 --- a/AttitudeManager/FlightModes/Inc/AM_ControlAlgorithm.hpp +++ b/AttitudeManager/FlightModes/Inc/flightmode.hpp @@ -15,14 +15,13 @@ namespace AM { class Flightmode { public: - Flightmode(){}; - - /// @brief Run the controls algorithm for the given flight model. - /// @param - /// @returns - virtual void run() = 0; + virtual ~Flightmode() = default; + virtual AttitudeManagerInput run(const AttitudeManagerInput& input) = 0; virtual void updatePid() = 0; + + protected: + Flightmode() = default; }; } // namespace AM diff --git a/AttitudeManager/FlightModes/Inc/manual.hpp b/AttitudeManager/FlightModes/Inc/manual.hpp new file mode 100644 index 00000000..be4338e2 --- /dev/null +++ b/AttitudeManager/FlightModes/Inc/manual.hpp @@ -0,0 +1,18 @@ +#ifndef ZPSW3_AM_MANUAL_HPP +#define ZPSW3_AM_MANUAL_HPP + +#include "flightmode.hpp" + +namespace AM { + +class Manual : public Flightmode { + public: + Manual() = default; + + AttitudeManagerInput run(const AttitudeManagerInput& input) override; + void updatePid() override; +}; + +} // namespace AM + +#endif // ZPSW3_AM_MANUAL_HPP diff --git a/AttitudeManager/FlightModes/Src/manual.cpp b/AttitudeManager/FlightModes/Src/manual.cpp new file mode 100644 index 00000000..0b80e325 --- /dev/null +++ b/AttitudeManager/FlightModes/Src/manual.cpp @@ -0,0 +1,12 @@ +#include "manual.hpp" +#include "CommonDataTypes.hpp" + +namespace AM { + +AttitudeManagerInput Manual::run(const AttitudeManagerInput& input) { + return input; +} + +void Manual::updatePid() {} + +} // namespace AM diff --git a/AttitudeManager/Inc/AM.hpp b/AttitudeManager/Inc/AM.hpp index 6b9a780c..559d7b1b 100644 --- a/AttitudeManager/Inc/AM.hpp +++ b/AttitudeManager/Inc/AM.hpp @@ -9,10 +9,10 @@ #ifndef ZPSW3_AM_HPP #define ZPSW3_AM_HPP -#include "AM_ControlAlgorithm.hpp" #include "CommonDataTypes.hpp" #include "config_foundation.hpp" #include "FreeRTOS.h" +#include "flightmode.hpp" #include "semphr.h" #ifdef TESTING #include @@ -21,9 +21,9 @@ namespace AM { typedef struct { - MotorChannel *motorInstance; - bool isInverted; - } MotorInstance_t; + MotorChannel *motorInstance; + bool isInverted; +} MotorInstance_t; class AttitudeManager { public: @@ -35,7 +35,7 @@ class AttitudeManager { ~AttitudeManager(); - void runControlLoopIteration(const AttitudeManagerInput& instructions); + void runControlLoopIteration(); private: #ifdef TESTING @@ -48,16 +48,15 @@ class AttitudeManager { #endif AttitudeManager(); - void outputToMotor(config::ControlAxis_t axis, uint8_t percent); + void outputToMotor(ControlAxis_t axis, uint8_t percent); static SemaphoreHandle_t control_inputs_mutex; - static struct AttitudeManagerInput control_inputs; Flightmode *controlAlgorithm_; MotorInstance_t *(&motorInstances_)[]; uint8_t (&numMotorsPerAxis_)[]; - + }; } // namespace AM diff --git a/AttitudeManager/Src/AM.cpp b/AttitudeManager/Src/AM.cpp index 7baafcb9..d8ada244 100644 --- a/AttitudeManager/Src/AM.cpp +++ b/AttitudeManager/Src/AM.cpp @@ -41,19 +41,25 @@ AttitudeManager::AttitudeManager(Flightmode* controlAlgorithm, MotorInstance_t numMotorsPerAxis_(numMotorsPerAxis) {}; -AttitudeManager::~AttitudeManager() +AttitudeManager::~AttitudeManager() {} -void AttitudeManager::runControlLoopIteration(const AttitudeManagerInput& instructions) { +void AttitudeManager::runControlLoopIteration() { // Process Instructions + AttitudeManagerInput control_inputs = getControlInputs(); // Run Control Algorithms - controlAlgorithm_->run(); + AttitudeManagerInput motor_outputs = controlAlgorithm_->run(control_inputs); // Write motor outputs + outputToMotor(yaw, static_cast(motor_outputs.yaw)); + outputToMotor(pitch, static_cast(motor_outputs.pitch)); + outputToMotor(roll, static_cast(motor_outputs.roll)); + outputToMotor(throttle, static_cast(motor_outputs.throttle)); + } -void AttitudeManager::outputToMotor(config::ControlAxis_t axis, uint8_t percent) { +void AttitudeManager::outputToMotor(ControlAxis_t axis, uint8_t percent) { // Move through the portion of the motorInstances array that matches the wanted axis. // The motorReferences array holds references to the wanted positions in the motorInstances array for (uint8_t motorCount{0}; motorCount < numMotorsPerAxis_[axis]; ++motorCount) { @@ -63,7 +69,7 @@ void AttitudeManager::outputToMotor(config::ControlAxis_t axis, uint8_t percent) motorInstances_[axis][motorCount].motorInstance->set(percent); } } - + } } // namespace AM diff --git a/AttitudeManager/Tests/AMTest.cpp b/AttitudeManager/Tests/AMTest.cpp index 5a331417..50772adc 100644 --- a/AttitudeManager/Tests/AMTest.cpp +++ b/AttitudeManager/Tests/AMTest.cpp @@ -1,29 +1,95 @@ #include #include #include "AM.hpp" +#include "CommonDataTypes.hpp" #include "config_foundation.hpp" #include "MockChannel.hpp" #include "MockFlightmode.hpp" namespace AM { +TEST(AttitudeManager, RunIteration) { + //TODO: This boilerplate setup code could probably be abstracted into a test fixture + MockFlightmode controlAlgorithm{}; + MotorInstance_t *motorInstances[NUM_CONTROL_AXIS]{nullptr}; + uint8_t numMotorsPerAxis[NUM_CONTROL_AXIS]{0}; + + MockChannel mockChannelReferences[4]{}; + + MotorInstance_t yawMotorReferences[] = { + { + .motorInstance = &mockChannelReferences[0], + .isInverted = false + } + }; + + MotorInstance_t pitchMotorReferences[] = { + { + .motorInstance = &mockChannelReferences[1], + .isInverted = false + } + }; + + MotorInstance_t rollMotorReferences[] = { + { + .motorInstance = &mockChannelReferences[2], + .isInverted = false + } + }; + + MotorInstance_t throttleMotorReferences[] = { + { + .motorInstance = &mockChannelReferences[3], + .isInverted = false + } + }; + + motorInstances[yaw] = yawMotorReferences; + motorInstances[pitch] = pitchMotorReferences; + motorInstances[roll] = rollMotorReferences; + motorInstances[throttle] = throttleMotorReferences; + + numMotorsPerAxis[yaw] = 1; + numMotorsPerAxis[pitch] = 1; + numMotorsPerAxis[roll] = 1; + numMotorsPerAxis[throttle] = 1; + + AM::AttitudeManager am{&controlAlgorithm, motorInstances, numMotorsPerAxis}; + + EXPECT_CALL(mockChannelReferences[0], set(12)); + EXPECT_CALL(mockChannelReferences[1], set(75)); + EXPECT_CALL(mockChannelReferences[2], set(100)); + EXPECT_CALL(mockChannelReferences[3], set(33)); + + AM::AttitudeManagerInput input { + .roll=100, + .pitch=75, + .yaw=12, + .throttle=33 + }; + + am.setControlInputs(input); + am.runControlLoopIteration(); +} + + TEST(AttitudeManagerOutputToMotor, NoMotors) { MockFlightmode controlAlgorithm{}; - MotorInstance_t *motorInstances[config::NUM_CONTROL_AXIS]{nullptr}; - uint8_t numMotorsPerAxis[config::NUM_CONTROL_AXIS]{0}; + MotorInstance_t *motorInstances[NUM_CONTROL_AXIS]{nullptr}; + uint8_t numMotorsPerAxis[NUM_CONTROL_AXIS]{0}; AM::AttitudeManager am{&controlAlgorithm, motorInstances, numMotorsPerAxis}; - am.outputToMotor(config::throttle, 40); - am.outputToMotor(config::pitch, 30); - am.outputToMotor(config::roll, 20); - am.outputToMotor(config::yaw, 10); + am.outputToMotor(throttle, 40); + am.outputToMotor(pitch, 30); + am.outputToMotor(roll, 20); + am.outputToMotor(yaw, 10); } TEST(AttitudeManagerOutputToMotor, MotorsOfSameAxis) { MockFlightmode controlAlgorithm{}; - MotorInstance_t *motorInstances[config::NUM_CONTROL_AXIS]{nullptr}; - uint8_t numMotorsPerAxis[config::NUM_CONTROL_AXIS]{0}; + MotorInstance_t *motorInstances[NUM_CONTROL_AXIS]{nullptr}; + uint8_t numMotorsPerAxis[NUM_CONTROL_AXIS]{0}; MockChannel mockChannelReferences[5]{}; @@ -50,9 +116,9 @@ TEST(AttitudeManagerOutputToMotor, MotorsOfSameAxis) { } }; - motorInstances[config::pitch] = pitchMotorReferences; + motorInstances[pitch] = pitchMotorReferences; - numMotorsPerAxis[config::pitch] = 5; + numMotorsPerAxis[pitch] = 5; AM::AttitudeManager am{&controlAlgorithm, motorInstances, numMotorsPerAxis}; @@ -63,10 +129,10 @@ TEST(AttitudeManagerOutputToMotor, MotorsOfSameAxis) { EXPECT_CALL(mockChannelReferences[3], set(30)); EXPECT_CALL(mockChannelReferences[4], set(30)); - am.outputToMotor(config::yaw, 10); - am.outputToMotor(config::throttle, 40); - am.outputToMotor(config::pitch, 30); - am.outputToMotor(config::roll, 20); + am.outputToMotor(yaw, 10); + am.outputToMotor(throttle, 40); + am.outputToMotor(pitch, 30); + am.outputToMotor(roll, 20); // Should set all of them EXPECT_CALL(mockChannelReferences[0], set(60)); @@ -75,13 +141,13 @@ TEST(AttitudeManagerOutputToMotor, MotorsOfSameAxis) { EXPECT_CALL(mockChannelReferences[3], set(60)); EXPECT_CALL(mockChannelReferences[4], set(60)); - am.outputToMotor(config::pitch, 60); + am.outputToMotor(pitch, 60); } TEST(AttitudeManagerOutputToMotor, setOutputInRandomAxisOrder) { MockFlightmode controlAlgorithm{}; - MotorInstance_t *motorInstances[config::NUM_CONTROL_AXIS]{nullptr}; - uint8_t numMotorsPerAxis[config::NUM_CONTROL_AXIS]{0}; + MotorInstance_t *motorInstances[NUM_CONTROL_AXIS]{nullptr}; + uint8_t numMotorsPerAxis[NUM_CONTROL_AXIS]{0}; MockChannel mockChannelReferences[4]{}; @@ -113,15 +179,15 @@ TEST(AttitudeManagerOutputToMotor, setOutputInRandomAxisOrder) { } }; - motorInstances[config::yaw] = yawMotorReferences; - motorInstances[config::pitch] = pitchMotorReferences; - motorInstances[config::roll] = rollMotorReferences; - motorInstances[config::throttle] = throttleMotorReferences; + motorInstances[yaw] = yawMotorReferences; + motorInstances[pitch] = pitchMotorReferences; + motorInstances[roll] = rollMotorReferences; + motorInstances[throttle] = throttleMotorReferences; - numMotorsPerAxis[config::yaw] = 1; - numMotorsPerAxis[config::pitch] = 1; - numMotorsPerAxis[config::roll] = 1; - numMotorsPerAxis[config::throttle] = 1; + numMotorsPerAxis[yaw] = 1; + numMotorsPerAxis[pitch] = 1; + numMotorsPerAxis[roll] = 1; + numMotorsPerAxis[throttle] = 1; AM::AttitudeManager am{&controlAlgorithm, motorInstances, numMotorsPerAxis}; @@ -131,16 +197,16 @@ TEST(AttitudeManagerOutputToMotor, setOutputInRandomAxisOrder) { EXPECT_CALL(mockChannelReferences[2], set(100)); EXPECT_CALL(mockChannelReferences[3], set(33)); - am.outputToMotor(config::yaw, 12); - am.outputToMotor(config::throttle, 33); - am.outputToMotor(config::pitch, 75); - am.outputToMotor(config::roll, 100); + am.outputToMotor(yaw, 12); + am.outputToMotor(throttle, 33); + am.outputToMotor(pitch, 75); + am.outputToMotor(roll, 100); } TEST(AttitudeManagerOutputToMotor, InvertedTest) { MockFlightmode controlAlgorithm{}; - MotorInstance_t *motorInstances[config::NUM_CONTROL_AXIS]{nullptr}; - uint8_t numMotorsPerAxis[config::NUM_CONTROL_AXIS]{0}; + MotorInstance_t *motorInstances[NUM_CONTROL_AXIS]{nullptr}; + uint8_t numMotorsPerAxis[NUM_CONTROL_AXIS]{0}; MockChannel mockChannelReferences[4]{}; @@ -172,15 +238,15 @@ TEST(AttitudeManagerOutputToMotor, InvertedTest) { } }; - motorInstances[config::yaw] = yawMotorReferences; - motorInstances[config::pitch] = pitchMotorReferences; - motorInstances[config::roll] = rollMotorReferences; - motorInstances[config::throttle] = throttleMotorReferences; + motorInstances[yaw] = yawMotorReferences; + motorInstances[pitch] = pitchMotorReferences; + motorInstances[roll] = rollMotorReferences; + motorInstances[throttle] = throttleMotorReferences; - numMotorsPerAxis[config::yaw] = 1; - numMotorsPerAxis[config::pitch] = 1; - numMotorsPerAxis[config::roll] = 1; - numMotorsPerAxis[config::throttle] = 1; + numMotorsPerAxis[yaw] = 1; + numMotorsPerAxis[pitch] = 1; + numMotorsPerAxis[roll] = 1; + numMotorsPerAxis[throttle] = 1; AM::AttitudeManager am{&controlAlgorithm, motorInstances, numMotorsPerAxis}; @@ -190,16 +256,16 @@ TEST(AttitudeManagerOutputToMotor, InvertedTest) { EXPECT_CALL(mockChannelReferences[2], set(0)); EXPECT_CALL(mockChannelReferences[3], set(67)); - am.outputToMotor(config::yaw, 12); - am.outputToMotor(config::pitch, 75); - am.outputToMotor(config::roll, 100); - am.outputToMotor(config::throttle, 33); + am.outputToMotor(yaw, 12); + am.outputToMotor(pitch, 75); + am.outputToMotor(roll, 100); + am.outputToMotor(throttle, 33); } TEST(AttitudeManagerOutputToMotor, CombinedTest) { MockFlightmode controlAlgorithm{}; - MotorInstance_t *motorInstances[config::NUM_CONTROL_AXIS]{nullptr}; - uint8_t numMotorsPerAxis[config::NUM_CONTROL_AXIS]{0}; + MotorInstance_t *motorInstances[NUM_CONTROL_AXIS]{nullptr}; + uint8_t numMotorsPerAxis[NUM_CONTROL_AXIS]{0}; MockChannel mockChannelReferences[8]{}; @@ -247,15 +313,15 @@ TEST(AttitudeManagerOutputToMotor, CombinedTest) { } }; - motorInstances[config::yaw] = yawMotorReferences; - motorInstances[config::pitch] = pitchMotorReferences; - motorInstances[config::roll] = rollMotorReferences; - motorInstances[config::throttle] = throttleMotorReferences; + motorInstances[yaw] = yawMotorReferences; + motorInstances[pitch] = pitchMotorReferences; + motorInstances[roll] = rollMotorReferences; + motorInstances[throttle] = throttleMotorReferences; - numMotorsPerAxis[config::yaw] = 2; - numMotorsPerAxis[config::pitch] = 3; - numMotorsPerAxis[config::roll] = 1; - numMotorsPerAxis[config::throttle] = 2; + numMotorsPerAxis[yaw] = 2; + numMotorsPerAxis[pitch] = 3; + numMotorsPerAxis[roll] = 1; + numMotorsPerAxis[throttle] = 2; AM::AttitudeManager am{&controlAlgorithm, motorInstances, numMotorsPerAxis}; @@ -269,10 +335,10 @@ TEST(AttitudeManagerOutputToMotor, CombinedTest) { EXPECT_CALL(mockChannelReferences[6], set(5)); EXPECT_CALL(mockChannelReferences[7], set(95)); - am.outputToMotor(config::yaw, 84); - am.outputToMotor(config::pitch, 27); - am.outputToMotor(config::roll, 94); - am.outputToMotor(config::throttle, 5); + am.outputToMotor(yaw, 84); + am.outputToMotor(pitch, 27); + am.outputToMotor(roll, 94); + am.outputToMotor(throttle, 5); } } \ No newline at end of file diff --git a/AttitudeManager/Tests/ExampleTest.cpp b/AttitudeManager/Tests/ExampleTest.cpp deleted file mode 100644 index 42ccd3b9..00000000 --- a/AttitudeManager/Tests/ExampleTest.cpp +++ /dev/null @@ -1,9 +0,0 @@ -#include - -// Demonstrate some basic assertions. -TEST(AttitudeManager, BasicAssertions) { - // Expect two strings not to be equal. - EXPECT_STRNE("hello", "world"); - // Expect equality. - EXPECT_EQ(7 * 6, 42); -} diff --git a/AttitudeManager/Tests/ManualControlTest.cpp b/AttitudeManager/Tests/ManualControlTest.cpp new file mode 100644 index 00000000..cda98f45 --- /dev/null +++ b/AttitudeManager/Tests/ManualControlTest.cpp @@ -0,0 +1,29 @@ +#include "manual.hpp" +#include "AM.hpp" + +#include + +class ManualModeTestFixture : public ::testing::TestWithParam{}; + +TEST_P(ManualModeTestFixture, check_inputs_are_expected) { + auto input = GetParam(); + + AM::Manual flightmode; + auto output = flightmode.run(input); + + EXPECT_EQ(input.roll, output.roll); + EXPECT_EQ(input.pitch, output.pitch); + EXPECT_EQ(input.yaw, output.yaw); + EXPECT_EQ(input.throttle, output.throttle); +} + +INSTANTIATE_TEST_CASE_P( + ManualModeTests, + ManualModeTestFixture, + ::testing::Values( + AM::AttitudeManagerInput{.roll = 0, .pitch = 0, .yaw = 0, .throttle = 0 }, + AM::AttitudeManagerInput{.roll = 0xDEAD, .pitch = 0xBEEF, .yaw = 0xFEED, .throttle = 0xFACE}, + AM::AttitudeManagerInput{.roll = 0.1f, .pitch = 0.5f, .yaw = 100, .throttle = 0.001f}, + AM::AttitudeManagerInput{.roll = 10, .pitch = -5.5, .yaw = -66.99, .throttle = -0xFFFF} + ) +); diff --git a/Common/Inc/CommonDataTypes.hpp b/Common/Inc/CommonDataTypes.hpp index 4cc90d4f..5afb6577 100644 --- a/Common/Inc/CommonDataTypes.hpp +++ b/Common/Inc/CommonDataTypes.hpp @@ -18,4 +18,11 @@ struct AttitudeManagerInput { } // Namespace AM +typedef enum { + yaw, + pitch, + roll, + throttle, + NUM_CONTROL_AXIS +} ControlAxis_t; #endif // ZPSW3_COMMON_DATATYPES_HPP diff --git a/Common/Inc/constrain.h b/Common/Inc/constrain.h index 4cfe40fc..ccf46009 100644 --- a/Common/Inc/constrain.h +++ b/Common/Inc/constrain.h @@ -1,6 +1,6 @@ #include -template +template static constexpr T constrain(const T input) { static_assert(max > min); return (input > max ? max : (input < min ? min : input)); diff --git a/Config_Models/config_foundation.hpp b/Config_Models/config_foundation.hpp index 461840f6..6b2cdd91 100644 --- a/Config_Models/config_foundation.hpp +++ b/Config_Models/config_foundation.hpp @@ -3,13 +3,14 @@ #include -#include "AM_ControlAlgorithm.hpp" +#include "flightmode.hpp" #include "temp_drivers.hpp" +#include "CommonDataTypes.hpp" namespace config { using percentage_t = float; - + //Define factory function to create drivers and flightmodes template BaseClass* constructObject() { @@ -23,15 +24,6 @@ namespace config /* Motor declarations */ - - typedef enum { - yaw, - pitch, - roll, - throttle, - NUM_CONTROL_AXIS - } ControlAxis_t; - typedef struct { ControlAxis_t axis; bool isInverted = false; @@ -89,7 +81,7 @@ namespace config ControlPID_t PIDValues = {}; ControlLimits_t controlLimits = {}; } ControlTuning_t; - + typedef struct { ControlTuning_t tuningData; ObjectFactory flightmodeConstructor; diff --git a/Config_Models/example_model/config.hpp b/Config_Models/example_model/config.hpp index ccb7e895..7c03e407 100644 --- a/Config_Models/example_model/config.hpp +++ b/Config_Models/example_model/config.hpp @@ -3,6 +3,7 @@ #include "config_foundation.hpp" #include "ZP_D_PWMChannel.hpp" +#include "manual.hpp" #include "tim.h" namespace config @@ -39,7 +40,7 @@ namespace config .driverConstructor = constructObject } }; - + constexpr uint8_t NUM_RC_INPUTS = sizeof(RCInputs)/sizeof(RCInput_t); @@ -55,7 +56,7 @@ namespace config .driverConstructor = constructObject } }; - + constexpr uint8_t NUM_GPS = sizeof(GPSArray)/sizeof(GPS_t); @@ -80,7 +81,7 @@ namespace config } } }, - .flightmodeConstructor = constructObject + .flightmodeConstructor = constructObject }, { //Flightmode2 .tuningData{ @@ -109,7 +110,7 @@ namespace config } } }, - .flightmodeConstructor = constructObject + .flightmodeConstructor = constructObject } }; diff --git a/Config_Models/temp_drivers.hpp b/Config_Models/temp_drivers.hpp index 130df1ee..72c66b97 100644 --- a/Config_Models/temp_drivers.hpp +++ b/Config_Models/temp_drivers.hpp @@ -18,20 +18,4 @@ class GPSDriver{}; class TempNEOM8Driver : public GPSDriver{}; class otherGPSDriver : public GPSDriver{}; -class ExampleFlightmode1 : public AM::Flightmode{ - public: - ExampleFlightmode1(){} - //TODO: Implement control algorithm functions in AM - void run(){}; - void updatePid(){}; -}; - -class ExampleFlightmode2 : public AM::Flightmode{ - public: - ExampleFlightmode2(){} - void run(){}; - void updatePid(){}; -}; - - #endif // ZPSW3_TEMP_DRIVERS_HPP \ No newline at end of file diff --git a/Testing/Mocks/Inc/MockFlightmode.hpp b/Testing/Mocks/Inc/MockFlightmode.hpp index cf87bd29..d70d542a 100644 --- a/Testing/Mocks/Inc/MockFlightmode.hpp +++ b/Testing/Mocks/Inc/MockFlightmode.hpp @@ -1,8 +1,10 @@ -#include "AM_ControlAlgorithm.hpp" +#include "flightmode.hpp" class MockFlightmode : public AM::Flightmode{ - public: +public: MockFlightmode(){} - void run(){}; + AM::AttitudeManagerInput run(const AM::AttitudeManagerInput& input) { + return input; + }; void updatePid(){}; }; \ No newline at end of file diff --git a/Testing/Stubs/Src/semphr.cpp b/Testing/Stubs/Src/semphr.cpp index ae65d6b5..46c21218 100644 --- a/Testing/Stubs/Src/semphr.cpp +++ b/Testing/Stubs/Src/semphr.cpp @@ -1,2 +1,2 @@ #include "semphr.h" -long xSemaphoreTake(int, int) {return 0;} \ No newline at end of file +long xSemaphoreTake(int, int) {return 1;} \ No newline at end of file diff --git a/Tools/Testing/CMakeLists.txt b/Tools/Testing/CMakeLists.txt index 1db36380..38243e32 100644 --- a/Tools/Testing/CMakeLists.txt +++ b/Tools/Testing/CMakeLists.txt @@ -108,7 +108,7 @@ include_directories(${COMMON_INC}) file(GLOB COMMON_CODE "${COMMON_FOLDER}/Tests/*.cpp" - # add necessary TelemetryManager source files below + # add necessary common source files below # "${COMMON_SRC}/foo.cpp" ) @@ -147,4 +147,4 @@ target_link_libraries(${PROJECT_NAME} ) include(GoogleTest) -gtest_discover_tests(${PROJECT_NAME}) \ No newline at end of file +gtest_discover_tests(${PROJECT_NAME}) From 57923d154edc9d4b52c8b9a831db0f8e842a4d5c Mon Sep 17 00:00:00 2001 From: Yaremadzulynsky <60479922+Yaremadzulynsky@users.noreply.github.com> Date: Tue, 19 Mar 2024 21:56:03 -0400 Subject: [PATCH 03/15] Tm/scaffolding (#40) --- .DS_Store | Bin 8196 -> 0 bytes .gitignore | 5 +- Drivers/.DS_Store | Bin 6148 -> 0 bytes TelemetryManager/Inc/CircularBuffer.hpp | 80 + .../Inc/GroundStationCommunication.hpp | 69 + TelemetryManager/Inc/ManagerCommunication.hpp | 0 TelemetryManager/Inc/MavlinkTranslator.hpp | 54 + TelemetryManager/Inc/TelemetryManager.hpp | 61 + TelemetryManager/Inc/TelemetryTask.hpp | 67 + TelemetryManager/Inc/incoming_data.h | 50 - TelemetryManager/Inc/mavlink_decoder.h | 85 - TelemetryManager/Inc/mavlink_encoder.h | 82 - .../Inc/official_mavlink_2_library/checksum.h | 95 - .../common/common.h | 2597 --- .../common/mavlink.h | 34 - .../mavlink_msg_actuator_control_target.h | 255 - .../mavlink_msg_actuator_output_status.h | 255 - .../common/mavlink_msg_adsb_vehicle.h | 505 - .../common/mavlink_msg_ais_vessel.h | 606 - .../common/mavlink_msg_altitude.h | 363 - .../common/mavlink_msg_att_pos_mocap.h | 331 - .../common/mavlink_msg_attitude.h | 363 - .../common/mavlink_msg_attitude_quaternion.h | 405 - .../mavlink_msg_attitude_quaternion_cov.h | 331 - .../common/mavlink_msg_attitude_target.h | 355 - .../common/mavlink_msg_auth_key.h | 213 - ...nk_msg_autopilot_state_for_gimbal_device.h | 505 - .../common/mavlink_msg_autopilot_version.h | 483 - .../common/mavlink_msg_battery_status.h | 531 - .../common/mavlink_msg_button_change.h | 263 - .../mavlink_msg_camera_capture_status.h | 363 - .../common/mavlink_msg_camera_fov_status.h | 430 - .../mavlink_msg_camera_image_captured.h | 456 - .../common/mavlink_msg_camera_information.h | 532 - .../common/mavlink_msg_camera_settings.h | 288 - .../mavlink_msg_camera_tracking_geo_status.h | 513 - ...mavlink_msg_camera_tracking_image_status.h | 438 - .../common/mavlink_msg_camera_trigger.h | 238 - .../common/mavlink_msg_can_filter_modify.h | 330 - .../common/mavlink_msg_can_frame.h | 330 - .../common/mavlink_msg_canfd_frame.h | 330 - .../common/mavlink_msg_cellular_config.h | 383 - .../common/mavlink_msg_cellular_status.h | 363 - .../mavlink_msg_change_operator_control.h | 280 - .../mavlink_msg_change_operator_control_ack.h | 263 - .../common/mavlink_msg_collision.h | 363 - .../common/mavlink_msg_command_ack.h | 338 - .../common/mavlink_msg_command_cancel.h | 263 - .../common/mavlink_msg_command_int.h | 513 - .../common/mavlink_msg_command_long.h | 463 - .../mavlink_msg_component_information.h | 306 - .../common/mavlink_msg_component_metadata.h | 255 - .../common/mavlink_msg_control_system_state.h | 607 - .../mavlink_msg_current_event_sequence.h | 238 - .../common/mavlink_msg_data_stream.h | 263 - .../mavlink_msg_data_transmission_handshake.h | 363 - .../common/mavlink_msg_debug.h | 263 - .../common/mavlink_msg_debug_float_array.h | 281 - .../common/mavlink_msg_debug_vect.h | 305 - .../common/mavlink_msg_distance_sensor.h | 480 - .../common/mavlink_msg_efi_status.h | 663 - .../common/mavlink_msg_encapsulated_data.h | 230 - .../common/mavlink_msg_esc_info.h | 407 - .../common/mavlink_msg_esc_status.h | 307 - .../common/mavlink_msg_estimator_status.h | 438 - .../common/mavlink_msg_event.h | 355 - .../common/mavlink_msg_extended_sys_state.h | 238 - .../common/mavlink_msg_fence_status.h | 313 - .../mavlink_msg_file_transfer_protocol.h | 280 - .../common/mavlink_msg_flight_information.h | 288 - .../common/mavlink_msg_follow_target.h | 459 - .../common/mavlink_msg_generator_status.h | 463 - ...avlink_msg_gimbal_device_attitude_status.h | 480 - .../mavlink_msg_gimbal_device_information.h | 582 - .../mavlink_msg_gimbal_device_set_attitude.h | 355 - .../mavlink_msg_gimbal_manager_information.h | 413 - .../mavlink_msg_gimbal_manager_set_attitude.h | 380 - ...nk_msg_gimbal_manager_set_manual_control.h | 388 - .../mavlink_msg_gimbal_manager_set_pitchyaw.h | 388 - .../mavlink_msg_gimbal_manager_status.h | 363 - .../common/mavlink_msg_global_position_int.h | 413 - .../mavlink_msg_global_position_int_cov.h | 430 - ...link_msg_global_vision_position_estimate.h | 405 - .../common/mavlink_msg_gps2_raw.h | 638 - .../common/mavlink_msg_gps2_rtk.h | 513 - .../common/mavlink_msg_gps_global_origin.h | 288 - .../common/mavlink_msg_gps_inject_data.h | 280 - .../common/mavlink_msg_gps_input.h | 663 - .../common/mavlink_msg_gps_raw_int.h | 588 - .../common/mavlink_msg_gps_rtcm_data.h | 255 - .../common/mavlink_msg_gps_rtk.h | 513 - .../common/mavlink_msg_gps_status.h | 334 - .../common/mavlink_msg_high_latency.h | 788 - .../common/mavlink_msg_high_latency2.h | 863 - .../common/mavlink_msg_highres_imu.h | 588 - .../mavlink_msg_hil_actuator_controls.h | 280 - .../common/mavlink_msg_hil_controls.h | 463 - .../common/mavlink_msg_hil_gps.h | 563 - .../common/mavlink_msg_hil_optical_flow.h | 488 - .../common/mavlink_msg_hil_rc_inputs_raw.h | 538 - .../common/mavlink_msg_hil_sensor.h | 588 - .../common/mavlink_msg_hil_state.h | 588 - .../common/mavlink_msg_hil_state_quaternion.h | 580 - .../common/mavlink_msg_home_position.h | 475 - .../common/mavlink_msg_hygrometer_sensor.h | 263 - .../common/mavlink_msg_isbd_link_status.h | 388 - .../common/mavlink_msg_landing_target.h | 530 - .../common/mavlink_msg_link_node_status.h | 463 - .../common/mavlink_msg_local_position_ned.h | 363 - .../mavlink_msg_local_position_ned_cov.h | 480 - ..._local_position_ned_system_global_offset.h | 363 - .../common/mavlink_msg_log_data.h | 280 - .../common/mavlink_msg_log_entry.h | 313 - .../common/mavlink_msg_log_erase.h | 238 - .../common/mavlink_msg_log_request_data.h | 313 - .../common/mavlink_msg_log_request_end.h | 238 - .../common/mavlink_msg_log_request_list.h | 288 - .../common/mavlink_msg_logging_ack.h | 263 - .../common/mavlink_msg_logging_data.h | 330 - .../common/mavlink_msg_logging_data_acked.h | 330 - .../common/mavlink_msg_mag_cal_report.h | 638 - .../common/mavlink_msg_manual_control.h | 438 - .../common/mavlink_msg_manual_setpoint.h | 363 - .../common/mavlink_msg_memory_vect.h | 280 - .../common/mavlink_msg_message_interval.h | 238 - .../common/mavlink_msg_mission_ack.h | 288 - .../common/mavlink_msg_mission_clear_all.h | 263 - .../common/mavlink_msg_mission_count.h | 288 - .../common/mavlink_msg_mission_current.h | 288 - .../common/mavlink_msg_mission_item.h | 563 - .../common/mavlink_msg_mission_item_int.h | 563 - .../common/mavlink_msg_mission_item_reached.h | 213 - .../common/mavlink_msg_mission_request.h | 288 - .../common/mavlink_msg_mission_request_int.h | 288 - .../common/mavlink_msg_mission_request_list.h | 263 - ...mavlink_msg_mission_request_partial_list.h | 313 - .../common/mavlink_msg_mission_set_current.h | 263 - .../mavlink_msg_mission_write_partial_list.h | 313 - .../common/mavlink_msg_mount_orientation.h | 313 - .../common/mavlink_msg_named_value_float.h | 255 - .../common/mavlink_msg_named_value_int.h | 255 - .../mavlink_msg_nav_controller_output.h | 388 - .../common/mavlink_msg_obstacle_distance.h | 405 - .../common/mavlink_msg_odometry.h | 632 - .../mavlink_msg_onboard_computer_status.h | 693 - .../mavlink_msg_open_drone_id_arm_status.h | 230 - ...mavlink_msg_open_drone_id_authentication.h | 406 - .../mavlink_msg_open_drone_id_basic_id.h | 331 - .../mavlink_msg_open_drone_id_location.h | 655 - .../mavlink_msg_open_drone_id_message_pack.h | 331 - .../mavlink_msg_open_drone_id_operator_id.h | 306 - .../mavlink_msg_open_drone_id_self_id.h | 306 - .../common/mavlink_msg_open_drone_id_system.h | 555 - .../mavlink_msg_open_drone_id_system_update.h | 338 - .../common/mavlink_msg_optical_flow.h | 438 - .../common/mavlink_msg_optical_flow_rad.h | 488 - .../mavlink_msg_orbit_execution_status.h | 338 - .../common/mavlink_msg_param_ext_ack.h | 281 - .../mavlink_msg_param_ext_request_list.h | 238 - .../mavlink_msg_param_ext_request_read.h | 280 - .../common/mavlink_msg_param_ext_set.h | 306 - .../common/mavlink_msg_param_ext_value.h | 306 - .../common/mavlink_msg_param_map_rc.h | 405 - .../common/mavlink_msg_param_request_list.h | 238 - .../common/mavlink_msg_param_request_read.h | 280 - .../common/mavlink_msg_param_set.h | 305 - .../common/mavlink_msg_param_value.h | 305 - .../common/mavlink_msg_ping.h | 288 - .../common/mavlink_msg_play_tune.h | 281 - .../common/mavlink_msg_play_tune_v2.h | 280 - .../mavlink_msg_position_target_global_int.h | 538 - .../mavlink_msg_position_target_local_ned.h | 538 - .../common/mavlink_msg_power_status.h | 263 - .../common/mavlink_msg_radio_status.h | 363 - .../common/mavlink_msg_raw_imu.h | 488 - .../common/mavlink_msg_raw_pressure.h | 313 - .../common/mavlink_msg_raw_rpm.h | 238 - .../common/mavlink_msg_rc_channels.h | 713 - .../common/mavlink_msg_rc_channels_override.h | 688 - .../common/mavlink_msg_rc_channels_raw.h | 463 - .../common/mavlink_msg_rc_channels_scaled.h | 463 - .../common/mavlink_msg_request_data_stream.h | 313 - .../common/mavlink_msg_request_event.h | 288 - .../common/mavlink_msg_resource_request.h | 306 - .../common/mavlink_msg_response_event_error.h | 313 - .../common/mavlink_msg_safety_allowed_area.h | 363 - .../mavlink_msg_safety_set_allowed_area.h | 413 - .../common/mavlink_msg_scaled_imu.h | 463 - .../common/mavlink_msg_scaled_imu2.h | 463 - .../common/mavlink_msg_scaled_imu3.h | 463 - .../common/mavlink_msg_scaled_pressure.h | 313 - .../common/mavlink_msg_scaled_pressure2.h | 313 - .../common/mavlink_msg_scaled_pressure3.h | 313 - .../common/mavlink_msg_serial_control.h | 380 - .../common/mavlink_msg_servo_output_raw.h | 638 - .../mavlink_msg_set_actuator_control_target.h | 305 - .../common/mavlink_msg_set_attitude_target.h | 431 - .../mavlink_msg_set_gps_global_origin.h | 313 - .../common/mavlink_msg_set_home_position.h | 480 - .../common/mavlink_msg_set_mode.h | 263 - ...vlink_msg_set_position_target_global_int.h | 588 - ...avlink_msg_set_position_target_local_ned.h | 588 - .../common/mavlink_msg_setup_signing.h | 280 - .../common/mavlink_msg_sim_state.h | 763 - .../common/mavlink_msg_smart_battery_info.h | 607 - .../common/mavlink_msg_statustext.h | 280 - .../common/mavlink_msg_storage_information.h | 495 - .../common/mavlink_msg_supported_tunes.h | 263 - .../common/mavlink_msg_sys_status.h | 588 - .../common/mavlink_msg_system_time.h | 238 - .../common/mavlink_msg_terrain_check.h | 238 - .../common/mavlink_msg_terrain_data.h | 305 - .../common/mavlink_msg_terrain_report.h | 363 - .../common/mavlink_msg_terrain_request.h | 288 - .../mavlink_msg_time_estimate_to_target.h | 313 - .../common/mavlink_msg_timesync.h | 288 - ...ink_msg_trajectory_representation_bezier.h | 359 - ..._msg_trajectory_representation_waypoints.h | 541 - .../common/mavlink_msg_tunnel.h | 305 - .../common/mavlink_msg_uavcan_node_info.h | 406 - .../common/mavlink_msg_uavcan_node_status.h | 338 - .../common/mavlink_msg_utm_global_position.h | 630 - .../common/mavlink_msg_v2_extension.h | 305 - .../common/mavlink_msg_vfr_hud.h | 338 - .../common/mavlink_msg_vibration.h | 363 - .../mavlink_msg_vicon_position_estimate.h | 380 - .../mavlink_msg_video_stream_information.h | 481 - .../common/mavlink_msg_video_stream_status.h | 388 - .../mavlink_msg_vision_position_estimate.h | 405 - .../mavlink_msg_vision_speed_estimate.h | 330 - .../common/mavlink_msg_wheel_distance.h | 255 - .../common/mavlink_msg_wifi_config_ap.h | 281 - .../common/mavlink_msg_winch_status.h | 388 - .../common/mavlink_msg_wind_cov.h | 413 - .../common/testsuite.h | 14741 ---------------- .../common/version.h | 14 - .../mavlink_conversions.h | 212 - .../mavlink_get_info.h | 83 - .../mavlink_helpers.h | 1154 -- .../mavlink_sha256.h | 235 - .../mavlink_types.h | 312 - .../message_definitions/ASLUAV.xml | 294 - .../message_definitions/AVSSUAS.xml | 198 - .../message_definitions/all.xml | 69 - .../message_definitions/ardupilotmega.xml | 1788 -- .../message_definitions/common.xml | 7606 -------- .../message_definitions/csAirLink.xml | 29 - .../message_definitions/cubepilot.xml | 48 - .../message_definitions/development.xml | 551 - .../message_definitions/icarous.xml | 48 - .../message_definitions/matrixpilot.xml | 349 - .../message_definitions/minimal.xml | 725 - .../message_definitions/paparazzi.xml | 38 - .../message_definitions/python_array_test.xml | 67 - .../message_definitions/standard.xml | 10 - .../message_definitions/storm32.xml | 433 - .../message_definitions/test.xml | 31 - .../message_definitions/uAvionix.xml | 122 - .../message_definitions/ualberta.xml | 66 - .../minimal/mavlink.h | 34 - .../minimal/mavlink_msg_heartbeat.h | 335 - .../minimal/mavlink_msg_protocol_version.h | 306 - .../minimal/minimal.h | 347 - .../minimal/testsuite.h | 164 - .../minimal/version.h | 14 - .../Inc/official_mavlink_2_library/protocol.h | 334 - .../standard/mavlink.h | 34 - .../standard/standard.h | 66 - .../standard/testsuite.h | 37 - .../standard/version.h | 14 - TelemetryManager/Src/CircularBuffer.cpp | 28 + .../Src/GroundStationCommunication.cpp | 40 + TelemetryManager/Src/ManagerCommunication.cpp | 0 TelemetryManager/Src/MavlinkTranslator.cpp | 23 + TelemetryManager/Src/TelemetryManager.cpp | 82 + TelemetryManager/Src/TelemetryTask.cpp | 18 + TelemetryManager/Src/mavlink_decoder.cpp | 109 - TelemetryManager/Src/mavlink_encoder.cpp | 63 - TelemetryManager/Tests/generic_test.cpp | 141 - TelemetryManager/Tests/temp.txt | 0 Tools/Testing/CMakeLists.txt | 2 +- 281 files changed, 526 insertions(+), 119324 deletions(-) delete mode 100644 .DS_Store delete mode 100644 Drivers/.DS_Store create mode 100644 TelemetryManager/Inc/CircularBuffer.hpp create mode 100644 TelemetryManager/Inc/GroundStationCommunication.hpp create mode 100644 TelemetryManager/Inc/ManagerCommunication.hpp create mode 100644 TelemetryManager/Inc/MavlinkTranslator.hpp create mode 100644 TelemetryManager/Inc/TelemetryManager.hpp create mode 100644 TelemetryManager/Inc/TelemetryTask.hpp delete mode 100644 TelemetryManager/Inc/incoming_data.h delete mode 100644 TelemetryManager/Inc/mavlink_decoder.h delete mode 100644 TelemetryManager/Inc/mavlink_encoder.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/checksum.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/common.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_actuator_control_target.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_actuator_output_status.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_adsb_vehicle.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_ais_vessel.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_altitude.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_att_pos_mocap.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_attitude.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_attitude_quaternion.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_attitude_quaternion_cov.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_attitude_target.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_auth_key.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_autopilot_state_for_gimbal_device.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_autopilot_version.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_battery_status.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_button_change.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_camera_capture_status.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_camera_fov_status.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_camera_image_captured.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_camera_information.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_camera_settings.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_camera_tracking_geo_status.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_camera_tracking_image_status.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_camera_trigger.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_can_filter_modify.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_can_frame.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_canfd_frame.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_cellular_config.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_cellular_status.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_change_operator_control.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_change_operator_control_ack.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_collision.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_command_ack.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_command_cancel.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_command_int.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_command_long.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_component_information.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_component_metadata.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_control_system_state.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_current_event_sequence.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_data_stream.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_data_transmission_handshake.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_debug.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_debug_float_array.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_debug_vect.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_distance_sensor.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_efi_status.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_encapsulated_data.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_esc_info.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_esc_status.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_estimator_status.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_event.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_extended_sys_state.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_fence_status.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_file_transfer_protocol.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_flight_information.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_follow_target.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_generator_status.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_gimbal_device_attitude_status.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_gimbal_device_information.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_gimbal_device_set_attitude.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_gimbal_manager_information.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_gimbal_manager_set_attitude.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_gimbal_manager_set_manual_control.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_gimbal_manager_set_pitchyaw.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_gimbal_manager_status.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_global_position_int.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_global_position_int_cov.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_global_vision_position_estimate.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_gps2_raw.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_gps2_rtk.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_gps_global_origin.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_gps_inject_data.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_gps_input.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_gps_raw_int.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_gps_rtcm_data.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_gps_rtk.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_gps_status.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_high_latency.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_high_latency2.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_highres_imu.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_hil_actuator_controls.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_hil_controls.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_hil_gps.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_hil_optical_flow.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_hil_rc_inputs_raw.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_hil_sensor.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_hil_state.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_hil_state_quaternion.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_home_position.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_hygrometer_sensor.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_isbd_link_status.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_landing_target.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_link_node_status.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_local_position_ned.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_local_position_ned_cov.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_local_position_ned_system_global_offset.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_log_data.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_log_entry.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_log_erase.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_log_request_data.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_log_request_end.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_log_request_list.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_logging_ack.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_logging_data.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_logging_data_acked.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_mag_cal_report.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_manual_control.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_manual_setpoint.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_memory_vect.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_message_interval.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_mission_ack.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_mission_clear_all.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_mission_count.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_mission_current.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_mission_item.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_mission_item_int.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_mission_item_reached.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_mission_request.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_mission_request_int.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_mission_request_list.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_mission_request_partial_list.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_mission_set_current.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_mission_write_partial_list.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_mount_orientation.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_named_value_float.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_named_value_int.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_nav_controller_output.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_obstacle_distance.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_odometry.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_onboard_computer_status.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_open_drone_id_arm_status.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_open_drone_id_authentication.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_open_drone_id_basic_id.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_open_drone_id_location.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_open_drone_id_message_pack.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_open_drone_id_operator_id.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_open_drone_id_self_id.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_open_drone_id_system.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_open_drone_id_system_update.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_optical_flow.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_optical_flow_rad.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_orbit_execution_status.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_param_ext_ack.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_param_ext_request_list.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_param_ext_request_read.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_param_ext_set.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_param_ext_value.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_param_map_rc.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_param_request_list.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_param_request_read.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_param_set.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_param_value.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_ping.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_play_tune.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_play_tune_v2.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_position_target_global_int.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_position_target_local_ned.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_power_status.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_radio_status.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_raw_imu.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_raw_pressure.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_raw_rpm.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_rc_channels.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_rc_channels_override.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_rc_channels_raw.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_rc_channels_scaled.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_request_data_stream.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_request_event.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_resource_request.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_response_event_error.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_safety_allowed_area.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_safety_set_allowed_area.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_scaled_imu.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_scaled_imu2.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_scaled_imu3.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_scaled_pressure.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_scaled_pressure2.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_scaled_pressure3.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_serial_control.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_servo_output_raw.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_set_actuator_control_target.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_set_attitude_target.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_set_gps_global_origin.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_set_home_position.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_set_mode.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_set_position_target_global_int.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_set_position_target_local_ned.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_setup_signing.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_sim_state.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_smart_battery_info.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_statustext.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_storage_information.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_supported_tunes.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_sys_status.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_system_time.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_terrain_check.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_terrain_data.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_terrain_report.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_terrain_request.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_time_estimate_to_target.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_timesync.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_trajectory_representation_bezier.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_trajectory_representation_waypoints.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_tunnel.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_uavcan_node_info.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_uavcan_node_status.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_utm_global_position.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_v2_extension.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_vfr_hud.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_vibration.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_vicon_position_estimate.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_video_stream_information.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_video_stream_status.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_vision_position_estimate.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_vision_speed_estimate.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_wheel_distance.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_wifi_config_ap.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_winch_status.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_wind_cov.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/testsuite.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/common/version.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/mavlink_conversions.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/mavlink_get_info.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/mavlink_helpers.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/mavlink_sha256.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/mavlink_types.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/message_definitions/ASLUAV.xml delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/message_definitions/AVSSUAS.xml delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/message_definitions/all.xml delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/message_definitions/ardupilotmega.xml delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/message_definitions/common.xml delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/message_definitions/csAirLink.xml delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/message_definitions/cubepilot.xml delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/message_definitions/development.xml delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/message_definitions/icarous.xml delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/message_definitions/matrixpilot.xml delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/message_definitions/minimal.xml delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/message_definitions/paparazzi.xml delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/message_definitions/python_array_test.xml delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/message_definitions/standard.xml delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/message_definitions/storm32.xml delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/message_definitions/test.xml delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/message_definitions/uAvionix.xml delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/message_definitions/ualberta.xml delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/minimal/mavlink.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/minimal/mavlink_msg_heartbeat.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/minimal/mavlink_msg_protocol_version.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/minimal/minimal.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/minimal/testsuite.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/minimal/version.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/protocol.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/standard/mavlink.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/standard/standard.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/standard/testsuite.h delete mode 100644 TelemetryManager/Inc/official_mavlink_2_library/standard/version.h create mode 100644 TelemetryManager/Src/CircularBuffer.cpp create mode 100644 TelemetryManager/Src/GroundStationCommunication.cpp create mode 100644 TelemetryManager/Src/ManagerCommunication.cpp create mode 100644 TelemetryManager/Src/MavlinkTranslator.cpp create mode 100644 TelemetryManager/Src/TelemetryManager.cpp create mode 100644 TelemetryManager/Src/TelemetryTask.cpp delete mode 100644 TelemetryManager/Src/mavlink_decoder.cpp delete mode 100644 TelemetryManager/Src/mavlink_encoder.cpp delete mode 100644 TelemetryManager/Tests/generic_test.cpp create mode 100644 TelemetryManager/Tests/temp.txt diff --git a/.DS_Store b/.DS_Store deleted file mode 100644 index 105a02e65b155def02db7a23d3bf514f1b4a0237..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 8196 zcmeHML2DC16n;~qjTW)qdR(k0QQKZbyqLyRyi}C*;z>;t)5@mXCaEAOtOu_m;z9A^ zwSxWx@gnF&`~!lBH~)eMzc(}8yvb&>35W=pS!Uic@4cDteLI=Avmqi?-mNbY%@I)% zmF4UVngNCNTvKJr_MCxK@Tai3R9%l++bK)m;TiA@cm_NJo&nFm|H1%rHkV>X-Zxs` zdImfL6UhMY4*@F6l9jQMdh0-=j{uMbbnAlqS-yb`tSng>8wm}HGOm!uRoNqkGVbUP ztX;{<*hu3}${s$Homtrviqf-V{6L$NDjDfp&wytj%>bX>3v`y6v`Jm({Qmg;4XJBI zl}as)YUnF|JNNm@uk#<5U44D1etScF8+aMOm8SRSr48Dpnln2cj?xwq!=o?1=U<%C z82ZL(MLi_hRt_FoWIV@cnYy^Z1n|_UL929|wose6Z@c&wKIMBzybs>KxwvpaB*pl>6VJBTVo6df6bnqOJVvXj_vP9@j}jwuo6*-D)1^asXyh%NzV z3s*#25+Cx*kAA(x^>gRMNxKG|F(jTW8;Qf_s%ff#t4+GcPn$aR&U#pjqL4FApUMS! z`FYwx!hCl(p|5Wo2{hZvh58kffwEPQ#Y;4FA1NzQ9KFQy{fVGVj3JR^*|<3LJTr6+ z3#^MD@Q|O%FiVN;;j;u=#<&t?zV!gSN2yBpsRP6fEVn$&L#!q4tFIE=Lp^%i(r6w7 z@Xykke&&q6fhgLDCNGLy9~p~!oy0PNUoWC@{078z5OGDgQmgs;ajYJpl~@<|_V%|_ z$D)U7u!TGSQ@uPVu{mIZp5ycXO7{2vNu=~FC22`O^t&|b2JzJ*&=d*TzdJB~c z+r>s|7c^|b{rWf#nfzgh`@rf-R>np`gYxe`1o-^l_s$@5>Nt5^zKxCJ=jLC%3Pk>P N->rTA*Zlnb<`116{*3?t diff --git a/.gitignore b/.gitignore index 970dcfd6..a9ec751a 100644 --- a/.gitignore +++ b/.gitignore @@ -19,9 +19,10 @@ # Executables *.exe *.out *.app +.DS_Store + .idea/ .vscode/ -.DS_Store/ -Tools/*/build +Tools/*/build/ Debug/ /.metadata/ diff --git a/Drivers/.DS_Store b/Drivers/.DS_Store deleted file mode 100644 index 5008ddfcf53c02e82d7eee2e57c38e5672ef89f6..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 6148 zcmeH~Jr2S!425mzP>H1@V-^m;4Wg<&0T*E43hX&L&p$$qDprKhvt+--jT7}7np#A3 zem<@ulZcFPQ@L2!n>{z**++&mCkOWA81W14cNZlEfg7;MkzE(HCqgga^y>{tEnwC%0;vJ&^%eQ zLs35+`xjp>T0 + +#include "FreeRTOS.h" +#include "TelemetryManager.hpp" +#include "task.h" +#ifndef TELEMETRYTASK_H +#define TELEMETRYTASK_H + +class TelemetryTask { + // Simple alias for a lambda function that takes a TelemetryManager reference as an argument. + using Callback = std::function; + + private: + // TM instance reference to be used in the callback. + TelemetryManager& tm; + // Callback function to be called when the timer interrupt is triggered. + Callback cbLambda; + // Handle to the task. Or should this be something else? Since we are doing a timer interrupt? + TaskHandle_t xHandle; + + /** + * @brief This is essentially a compatibility/wrapper function that allows us to use a lambda + * function which has a class instance as an argument as a callback for the timer interrupt. + * This allows us to access TM within the lambda function. + * + * @param pvParameters - The TelemetryTask object. + */ + static void TaskTrampoline(void* pvParameters); + + public: + /** + * @brief Construct a new Timer TelemetryTask object which will call the given lambda function + * at the given interval. This will allow easier scheduling of data transfer or any TM tasks + * which need to happen at a regular interval with FreeRTOS. + * + * @param taskName - The name of the task. + * @param stackSize - The size of the stack for the task. + * @param uxPriority - The priority of the task. + * @param tm - The TelemetryManager object. + * @param cbLambda - The callback function to be called when the timer interrupt is triggered. + */ + TelemetryTask(const char* taskName, int stackSize, UBaseType_t uxPriority, TelemetryManager& tm, + Callback cbLambda); + + /** + * @brief Destroy the Timer Interrupt object. + * + */ + ~TelemetryTask(); +}; + +#endif diff --git a/TelemetryManager/Inc/incoming_data.h b/TelemetryManager/Inc/incoming_data.h deleted file mode 100644 index 8337f004..00000000 --- a/TelemetryManager/Inc/incoming_data.h +++ /dev/null @@ -1,50 +0,0 @@ -// -// Created by Yarema Dzulynsky on 2023-08-30. -// - -#ifndef ZEROPILOT_SW_3_5_3_INCOMINGDATA_H -#define ZEROPILOT_SW_3_5_3_INCOMINGDATA_H - -/** - * @brief Represents a structure for incoming navigation data. - * - * This structure is designed to hold various navigation parameters such as - * latitude, longitude, velocities in various axes, altitude, and the pitch, - * roll, and yaw angles. Additionally, for each data point, there is a - * corresponding boolean flag to indicate whether that data point has been - * initialized or not. This helps in ensuring data validity before processing. - * - * @note This structure should be modified to suit the needs of the project. - * This is just a preliminary structure to get us started. - */ -struct IncomingData { - - float latitude = 0; ///< Latitude of the drone in degrees. - bool isLatitudeInitialized = false;///< Flag indicating if latitude value has been set. - - float longitude = 0; ///< Longitude of the drone in degrees. - bool isLongitudeInitialized = false;///< Flag indicating if longitude value has been set. - - float vx = 0; ///< Velocity in the X-axis (m/s). - bool isVxInitialized = false; ///< Flag indicating if vx value has been set. - - float vy = 0; ///< Velocity in the Y-axis (m/s). - bool isVyInitialized = false; ///< Flag indicating if vy value has been set. - - float vz = 0; ///< Velocity in the Z-axis (m/s). - bool isVzInitialized = false; ///< Flag indicating if vz value has been set. - - int altitude = 0; ///< Altitude of the drone in meters. - bool isAltitudeInitialized = false;///< Flag indicating if altitude value has been set. - - float pitch = 0; ///< Pitch angle of the drone in degrees. - bool isPitchInitialized = false; ///< Flag indicating if pitch value has been set. - - float roll = 0; ///< Roll angle of the drone in degrees. - bool isRollInitialized = false; ///< Flag indicating if roll value has been set. - - float yaw = 0; ///< Yaw angle of the drone in degrees. - bool isYawInitialized = false; ///< Flag indicating if yaw value has been set. -}; - -#endif // ZEROPILOT_SW_3_5_3_INCOMINGDATA_H diff --git a/TelemetryManager/Inc/mavlink_decoder.h b/TelemetryManager/Inc/mavlink_decoder.h deleted file mode 100644 index b242b6f7..00000000 --- a/TelemetryManager/Inc/mavlink_decoder.h +++ /dev/null @@ -1,85 +0,0 @@ -// -// Created by Yarema Dzulynsky on 2023-07-10. -// - -#ifndef WARGMAVLINKSUPPORT_MAVLINKDECODER_H -#define WARGMAVLINKSUPPORT_MAVLINKDECODER_H - -#include -#include -#include - -#include "official_mavlink_2_library/common/mavlink.h" - - - -/** - * Macro for registering a decoder function for a specific message type. - * @param msgId (int) - the message id of the message type to be decoded. - * @param baseName (string) - the base name of the message type to be decoded. Ex. for - * mavlink_attitude_t, the base name is attitude. Essentially, whatever is in between mavlink_ and - * _t form the message you would like to register. The base name is used to generate the decoder - * function name. Ex. for mavlink_attitude_t, the decoder function name is - * mavlink_msg_attitude_decode. - * @param postProcessor ([](mavlink_**baseName**_t &message)) - the post processor function to be - * called after the message. This function must take in a reference to the message type that is - * being decoded. You can then use this reference to access the message fields. Ex. message.roll, - * message.pitch, etc. Now do what you want with them! :) - * @example REGISTER_DECODER(MAVLINK_MSG_ID_ATTITUDE, attitude, [](mavlink_attitude_t &message) { - * //print out the message - * std::cout << "ATTITUDE" << std::endl; - * std::cout << "roll: " << message.roll << std::endl; - * std::cout << "pitch: " << message.pitch << std::endl; - * std::cout << "yaw: " << message.yaw << std::endl; - * std::cout << "rollspeed: " << message.rollspeed << std::endl; - * std::cout << "pitchspeed: " << message.pitchspeed << std::endl; - * }; - */ -#define REGISTER_DECODER(msgId, baseName, postProcessor) \ - decodingFunctions[msgId] = [](mavlink_message_t &msg) { \ - mavlink_##baseName##_t msgType; \ - mavlink_msg_##baseName##_decode(&msg, &msgType); \ - MavlinkDecoder::decodedMessages++; \ - postProcessor(msgType); \ - }; - - -class MavlinkDecoder { - public: - - std::unordered_map> decodingFunctions; - /** - * The number of decoded messages. This is used for test cases - */ - static long decodedMessages; - - public: - /** - * Default constructor. - * Register message types with their decoders and post-decoding callbacks here. - * Without using REGISTER_DECODER, the decoder map remains unpopulated. - */ - MavlinkDecoder(); - - /** - * Default destructor. - * No specific cleanup is required since no dynamic memory is utilized. - */ - ~MavlinkDecoder(); - - /** - * Unpacks the message, triggering the respective callback set during construction. - * @param msg - The preformatted mavlink message, ready for decoding. - * @param isMessageDecoded - Flag that indicates successful decoding. - */ - void decodeMsg(mavlink_message_t &msg, bool &isMessageDecoded); - - /** - * Transforms a byte sequence into mavlink messages, then activates the respective callbacks. - * @param buffer - Byte sequence for parsing. - * @param bufferSize - Length of the byte sequence. - */ - void parseBytesToMavlinkMsgs(uint8_t *buffer, std::size_t bufferSize); -}; - -#endif // WARGMAVLINKSUPPORT_MAVLINKDECODER_H diff --git a/TelemetryManager/Inc/mavlink_encoder.h b/TelemetryManager/Inc/mavlink_encoder.h deleted file mode 100644 index f7cfc08f..00000000 --- a/TelemetryManager/Inc/mavlink_encoder.h +++ /dev/null @@ -1,82 +0,0 @@ -// -// Created by Yarema Dzulynsky on 2023-07-24. -// - -#ifndef WARGMAVLINKSUPPORT_BASICMAVLINKENCODER_H -#define WARGMAVLINKSUPPORT_BASICMAVLINKENCODER_H - -#include - -#include "official_mavlink_2_library/common/mavlink.h" -#include "incoming_data.h" - -/** - * @brief ENCODE_MESSAGE macro for MAVLink message packing - * - * This macro is used to pack MAVLink messages of various types. It takes the base name of the MAVLink - * message and a variable number of arguments specific to the message type. It creates an anonymous lambda - * function that packs the provided arguments into a MAVLink message and converts it to a byte buffer. - * - * @param baseName The base name of the MAVLink message (e.g., HEARTBEAT, COMMAND_LONG, etc.). - * @param ... Variable number of arguments specific to the MAVLink message type. These arguments - * are used for populating the fields of the message. - * - * @return std::size_t The length of the byte buffer containing the packed MAVLink message. - * - * @note The ENCODE_MESSAGE macro uses lambda functions to encapsulate the packing process for different - * MAVLink message types. The resulting lambda function can be used to efficiently pack MAVLink messages - * and obtain the length of the packed buffer. - * - * @note The ENCODE_MESSAGE macro is used in the following way: - * ENCODE_MESSAGE(HEARTBEAT, 1, 2, 3, 4, 5, 6, 7, 8, 9)(msg, buffer); - * where HEARTBEAT is the base name of the MAVLink message and 1, 2, 3, 4, 5, 6, 7, 8, 9 are the - * arguments specific to the HEARTBEAT message type. - * The parameters msg and buffer are passed by reference to the lambda function and are used to - * store the packed MAVLink message and the packed buffer, respectively. - * - */ -#define ENCODE_MESSAGE(baseName, ...) \ - ([&](mavlink_message_t& msg, uint8_t* buffer) -> std::size_t { \ - mavlink_msg_##baseName##_pack(0, 0, &msg, __VA_ARGS__); \ - std::size_t bufferLen = mavlink_msg_to_send_buffer(buffer, &msg); \ - return bufferLen; \ - }) - - -/** - * Setting a predefined buffer size, derived from the maximum packet length allowed by MAVLink. - * @note IMPORTANT: IF THE THE MAX_ARRAY_BUFFER_SIZE < SIZE OF BYTES INCOMING MEMORY MAY - * BE OVERWRITTEN! - */ -#define MAX_ARRAY_BUFFER_SIZE (10 * MAVLINK_MAX_PACKET_LEN) - -/** - * @brief Class dedicated to MAVLink message encoding. - * - * The 'MavlinkEncoder' class provides an interface and underlying functionality for MAVLink message - * encoding, using associated parameters and defined message types. - */ -class MavlinkEncoder { - public: - // The message object that's currently targeted for encoding. - mavlink_message_t currentMessage; - - // Default constructor for the MavlinkEncoder class. - MavlinkEncoder(); - - /** - * @brief Identifies the appropriate encoding function based on the incoming data. - * - * This function seeks the suitable encoding mechanism in line with the data specifics - * and subsequently populates the output buffer. - * - * @param data Incoming data to be encoded. - * @param outputBuffer The buffer to store the encoded data. - * @param maxBufferSize The maximum size the output buffer can occupy. - * - * @return Returns the size (in bytes) used in the output buffer. - */ - size_t packIntoMavlinkByteArray(IncomingData& data, uint8_t* outputBuffer, size_t maxBufferSize); -}; - -#endif //WARGMAVLINKSUPPORT_BASICMAVLINKENCODER_H diff --git a/TelemetryManager/Inc/official_mavlink_2_library/checksum.h b/TelemetryManager/Inc/official_mavlink_2_library/checksum.h deleted file mode 100644 index d0d011d1..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/checksum.h +++ /dev/null @@ -1,95 +0,0 @@ -#pragma once - -#if defined(MAVLINK_USE_CXX_NAMESPACE) -namespace mavlink { -#elif defined(__cplusplus) -extern "C" { -#endif - -// Visual Studio versions before 2010 don't have stdint.h, so we just error out. -#if (defined _MSC_VER) && (_MSC_VER < 1600) -#error "The C-MAVLink implementation requires Visual Studio 2010 or greater" -#endif - -#include - -/** - * - * CALCULATE THE CHECKSUM - * - */ - -#define X25_INIT_CRC 0xffff -#define X25_VALIDATE_CRC 0xf0b8 - -#ifndef HAVE_CRC_ACCUMULATE -/** - * @brief Accumulate the CRC16_MCRF4XX checksum by adding one char at a time. - * - * The checksum function adds the hash of one char at a time to the - * 16 bit checksum (uint16_t). - * - * @param data new char to hash - * @param crcAccum the already accumulated checksum - **/ -static inline void crc_accumulate(uint8_t data, uint16_t *crcAccum) -{ - /*Accumulate one byte of data into the CRC*/ - uint8_t tmp; - - tmp = data ^ (uint8_t)(*crcAccum &0xff); - tmp ^= (tmp<<4); - *crcAccum = (*crcAccum>>8) ^ (tmp<<8) ^ (tmp <<3) ^ (tmp>>4); -} -#endif - - -/** - * @brief Initialize the buffer for the MCRF4XX CRC16 - * - * @param crcAccum the 16 bit MCRF4XX CRC16 - */ -static inline void crc_init(uint16_t* crcAccum) -{ - *crcAccum = X25_INIT_CRC; -} - - -/** - * @brief Calculates the CRC16_MCRF4XX checksum on a byte buffer - * - * @param pBuffer buffer containing the byte array to hash - * @param length length of the byte array - * @return the checksum over the buffer bytes - **/ -static inline uint16_t crc_calculate(const uint8_t* pBuffer, uint16_t length) -{ - uint16_t crcTmp; - crc_init(&crcTmp); - while (length--) { - crc_accumulate(*pBuffer++, &crcTmp); - } - return crcTmp; -} - - -/** - * @brief Accumulate the MCRF4XX CRC16 by adding an array of bytes - * - * The checksum function adds the hash of one char at a time to the - * 16 bit checksum (uint16_t). - * - * @param data new bytes to hash - * @param crcAccum the already accumulated checksum - **/ -static inline void crc_accumulate_buffer(uint16_t *crcAccum, const char *pBuffer, uint16_t length) -{ - const uint8_t *p = (const uint8_t *)pBuffer; - while (length--) { - crc_accumulate(*p++, crcAccum); - } -} - -#if defined(MAVLINK_USE_CXX_NAMESPACE) || defined(__cplusplus) -} -#endif diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/common.h b/TelemetryManager/Inc/official_mavlink_2_library/common/common.h deleted file mode 100644 index 28f531a8..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/common.h +++ /dev/null @@ -1,2597 +0,0 @@ -/** @file - * @brief MAVLink comm protocol generated from common.xml - * @see http://mavlink.org - */ -#pragma once -#ifndef MAVLINK_COMMON_H -#define MAVLINK_COMMON_H - -#ifndef MAVLINK_H - #error Wrong include order: MAVLINK_COMMON.H MUST NOT BE DIRECTLY USED. Include mavlink.h from the same directory instead or set ALL AND EVERY defines from MAVLINK.H manually accordingly, including the #define MAVLINK_H call. -#endif - -#define MAVLINK_COMMON_XML_HASH -2384891800141893948 - -#ifdef __cplusplus -extern "C" { -#endif - -// MESSAGE LENGTHS AND CRCS - -#ifndef MAVLINK_MESSAGE_LENGTHS -#define MAVLINK_MESSAGE_LENGTHS {} -#endif - -#ifndef MAVLINK_MESSAGE_CRCS -#define MAVLINK_MESSAGE_CRCS {{0, 50, 9, 9, 0, 0, 0}, {1, 124, 31, 43, 0, 0, 0}, {2, 137, 12, 12, 0, 0, 0}, {4, 237, 14, 14, 3, 12, 13}, {5, 217, 28, 28, 1, 0, 0}, {6, 104, 3, 3, 0, 0, 0}, {7, 119, 32, 32, 0, 0, 0}, {8, 117, 36, 36, 0, 0, 0}, {11, 89, 6, 6, 1, 4, 0}, {20, 214, 20, 20, 3, 2, 3}, {21, 159, 2, 2, 3, 0, 1}, {22, 220, 25, 25, 0, 0, 0}, {23, 168, 23, 23, 3, 4, 5}, {24, 24, 30, 52, 0, 0, 0}, {25, 23, 101, 101, 0, 0, 0}, {26, 170, 22, 24, 0, 0, 0}, {27, 144, 26, 29, 0, 0, 0}, {28, 67, 16, 16, 0, 0, 0}, {29, 115, 14, 16, 0, 0, 0}, {30, 39, 28, 28, 0, 0, 0}, {31, 246, 32, 48, 0, 0, 0}, {32, 185, 28, 28, 0, 0, 0}, {33, 104, 28, 28, 0, 0, 0}, {34, 237, 22, 22, 0, 0, 0}, {35, 244, 22, 22, 0, 0, 0}, {36, 222, 21, 37, 0, 0, 0}, {37, 212, 6, 7, 3, 4, 5}, {38, 9, 6, 7, 3, 4, 5}, {39, 254, 37, 38, 3, 32, 33}, {40, 230, 4, 5, 3, 2, 3}, {41, 28, 4, 4, 3, 2, 3}, {42, 28, 2, 6, 0, 0, 0}, {43, 132, 2, 3, 3, 0, 1}, {44, 221, 4, 5, 3, 2, 3}, {45, 232, 2, 3, 3, 0, 1}, {46, 11, 2, 2, 0, 0, 0}, {47, 153, 3, 4, 3, 0, 1}, {48, 41, 13, 21, 1, 12, 0}, {49, 39, 12, 20, 0, 0, 0}, {50, 78, 37, 37, 3, 18, 19}, {51, 196, 4, 5, 3, 2, 3}, {54, 15, 27, 27, 3, 24, 25}, {55, 3, 25, 25, 0, 0, 0}, {61, 167, 72, 72, 0, 0, 0}, {62, 183, 26, 26, 0, 0, 0}, {63, 119, 181, 181, 0, 0, 0}, {64, 191, 225, 225, 0, 0, 0}, {65, 118, 42, 42, 0, 0, 0}, {66, 148, 6, 6, 3, 2, 3}, {67, 21, 4, 4, 0, 0, 0}, {69, 243, 11, 18, 1, 10, 0}, {70, 124, 18, 38, 3, 16, 17}, {73, 38, 37, 38, 3, 32, 33}, {74, 20, 20, 20, 0, 0, 0}, {75, 158, 35, 35, 3, 30, 31}, {76, 152, 33, 33, 3, 30, 31}, {77, 143, 3, 10, 3, 8, 9}, {80, 14, 4, 4, 3, 2, 3}, {81, 106, 22, 22, 0, 0, 0}, {82, 49, 39, 51, 3, 36, 37}, {83, 22, 37, 37, 0, 0, 0}, {84, 143, 53, 53, 3, 50, 51}, {85, 140, 51, 51, 0, 0, 0}, {86, 5, 53, 53, 3, 50, 51}, {87, 150, 51, 51, 0, 0, 0}, {89, 231, 28, 28, 0, 0, 0}, {90, 183, 56, 56, 0, 0, 0}, {91, 63, 42, 42, 0, 0, 0}, {92, 54, 33, 33, 0, 0, 0}, {93, 47, 81, 81, 0, 0, 0}, {100, 175, 26, 34, 0, 0, 0}, {101, 102, 32, 117, 0, 0, 0}, {102, 158, 32, 117, 0, 0, 0}, {103, 208, 20, 57, 0, 0, 0}, {104, 56, 32, 116, 0, 0, 0}, {105, 93, 62, 63, 0, 0, 0}, {106, 138, 44, 44, 0, 0, 0}, {107, 108, 64, 65, 0, 0, 0}, {108, 32, 84, 92, 0, 0, 0}, {109, 185, 9, 9, 0, 0, 0}, {110, 84, 254, 254, 3, 1, 2}, {111, 34, 16, 18, 3, 16, 17}, {112, 174, 12, 12, 0, 0, 0}, {113, 124, 36, 39, 0, 0, 0}, {114, 237, 44, 44, 0, 0, 0}, {115, 4, 64, 64, 0, 0, 0}, {116, 76, 22, 24, 0, 0, 0}, {117, 128, 6, 6, 3, 4, 5}, {118, 56, 14, 14, 0, 0, 0}, {119, 116, 12, 12, 3, 10, 11}, {120, 134, 97, 97, 0, 0, 0}, {121, 237, 2, 2, 3, 0, 1}, {122, 203, 2, 2, 3, 0, 1}, {123, 250, 113, 113, 3, 0, 1}, {124, 87, 35, 57, 0, 0, 0}, {125, 203, 6, 6, 0, 0, 0}, {126, 220, 79, 81, 3, 79, 80}, {127, 25, 35, 35, 0, 0, 0}, {128, 226, 35, 35, 0, 0, 0}, {129, 46, 22, 24, 0, 0, 0}, {130, 29, 13, 13, 0, 0, 0}, {131, 223, 255, 255, 0, 0, 0}, {132, 85, 14, 39, 0, 0, 0}, {133, 6, 18, 18, 0, 0, 0}, {134, 229, 43, 43, 0, 0, 0}, {135, 203, 8, 8, 0, 0, 0}, {136, 1, 22, 22, 0, 0, 0}, {137, 195, 14, 16, 0, 0, 0}, {138, 109, 36, 120, 0, 0, 0}, {139, 168, 43, 43, 3, 41, 42}, {140, 181, 41, 41, 0, 0, 0}, {141, 47, 32, 32, 0, 0, 0}, {142, 72, 243, 243, 0, 0, 0}, {143, 131, 14, 16, 0, 0, 0}, {144, 127, 93, 93, 0, 0, 0}, {146, 103, 100, 100, 0, 0, 0}, {147, 154, 36, 54, 0, 0, 0}, {148, 178, 60, 78, 0, 0, 0}, {149, 200, 30, 60, 0, 0, 0}, {162, 189, 8, 9, 0, 0, 0}, {192, 36, 44, 54, 0, 0, 0}, {225, 208, 65, 73, 0, 0, 0}, {230, 163, 42, 42, 0, 0, 0}, {231, 105, 40, 40, 0, 0, 0}, {232, 151, 63, 65, 0, 0, 0}, {233, 35, 182, 182, 0, 0, 0}, {234, 150, 40, 40, 0, 0, 0}, {235, 179, 42, 42, 0, 0, 0}, {241, 90, 32, 32, 0, 0, 0}, {242, 104, 52, 60, 0, 0, 0}, {243, 85, 53, 61, 1, 52, 0}, {244, 95, 6, 6, 0, 0, 0}, {245, 130, 2, 2, 0, 0, 0}, {246, 184, 38, 38, 0, 0, 0}, {247, 81, 19, 19, 0, 0, 0}, {248, 8, 254, 254, 3, 3, 4}, {249, 204, 36, 36, 0, 0, 0}, {250, 49, 30, 30, 0, 0, 0}, {251, 170, 18, 18, 0, 0, 0}, {252, 44, 18, 18, 0, 0, 0}, {253, 83, 51, 54, 0, 0, 0}, {254, 46, 9, 9, 0, 0, 0}, {256, 71, 42, 42, 3, 8, 9}, {257, 131, 9, 9, 0, 0, 0}, {258, 187, 32, 232, 3, 0, 1}, {259, 92, 235, 236, 0, 0, 0}, {260, 146, 5, 13, 0, 0, 0}, {261, 179, 27, 61, 0, 0, 0}, {262, 12, 18, 22, 0, 0, 0}, {263, 133, 255, 255, 0, 0, 0}, {264, 49, 28, 28, 0, 0, 0}, {265, 26, 16, 20, 0, 0, 0}, {266, 193, 255, 255, 3, 2, 3}, {267, 35, 255, 255, 3, 2, 3}, {268, 14, 4, 4, 3, 2, 3}, {269, 109, 213, 213, 0, 0, 0}, {270, 59, 19, 19, 0, 0, 0}, {271, 22, 52, 52, 0, 0, 0}, {275, 126, 31, 31, 0, 0, 0}, {276, 18, 49, 49, 0, 0, 0}, {280, 70, 33, 33, 0, 0, 0}, {281, 48, 13, 13, 0, 0, 0}, {282, 123, 35, 35, 3, 32, 33}, {283, 74, 144, 145, 0, 0, 0}, {284, 99, 32, 32, 3, 30, 31}, {285, 137, 40, 49, 3, 38, 39}, {286, 210, 53, 57, 3, 50, 51}, {287, 1, 23, 23, 3, 20, 21}, {288, 20, 23, 23, 3, 20, 21}, {290, 251, 46, 46, 0, 0, 0}, {291, 10, 57, 57, 0, 0, 0}, {299, 19, 96, 98, 0, 0, 0}, {300, 217, 22, 22, 0, 0, 0}, {301, 243, 58, 58, 0, 0, 0}, {310, 28, 17, 17, 0, 0, 0}, {311, 95, 116, 116, 0, 0, 0}, {320, 243, 20, 20, 3, 2, 3}, {321, 88, 2, 2, 3, 0, 1}, {322, 243, 149, 149, 0, 0, 0}, {323, 78, 147, 147, 3, 0, 1}, {324, 132, 146, 146, 0, 0, 0}, {330, 23, 158, 167, 0, 0, 0}, {331, 91, 230, 233, 0, 0, 0}, {332, 236, 239, 239, 0, 0, 0}, {333, 231, 109, 109, 0, 0, 0}, {334, 72, 10, 10, 0, 0, 0}, {335, 225, 24, 24, 0, 0, 0}, {336, 245, 84, 84, 0, 0, 0}, {339, 199, 5, 5, 0, 0, 0}, {340, 99, 70, 70, 0, 0, 0}, {350, 232, 20, 252, 0, 0, 0}, {360, 11, 25, 25, 0, 0, 0}, {370, 75, 87, 109, 0, 0, 0}, {373, 117, 42, 42, 0, 0, 0}, {375, 251, 140, 140, 0, 0, 0}, {380, 232, 20, 20, 0, 0, 0}, {385, 147, 133, 133, 3, 2, 3}, {386, 132, 16, 16, 3, 4, 5}, {387, 4, 72, 72, 3, 4, 5}, {388, 8, 37, 37, 3, 32, 33}, {390, 156, 238, 238, 0, 0, 0}, {395, 0, 212, 212, 0, 0, 0}, {397, 182, 108, 108, 0, 0, 0}, {400, 110, 254, 254, 3, 4, 5}, {401, 183, 6, 6, 3, 4, 5}, {410, 160, 53, 53, 0, 0, 0}, {411, 106, 3, 3, 0, 0, 0}, {412, 33, 6, 6, 3, 4, 5}, {413, 77, 7, 7, 3, 4, 5}, {9000, 113, 137, 137, 0, 0, 0}, {9005, 117, 34, 34, 0, 0, 0}, {12900, 114, 44, 44, 3, 0, 1}, {12901, 254, 59, 59, 3, 30, 31}, {12902, 140, 53, 53, 3, 4, 5}, {12903, 249, 46, 46, 3, 0, 1}, {12904, 77, 54, 54, 3, 28, 29}, {12905, 49, 43, 43, 3, 0, 1}, {12915, 94, 249, 249, 3, 0, 1}, {12918, 139, 51, 51, 0, 0, 0}, {12919, 7, 18, 18, 3, 16, 17}, {12920, 20, 5, 5, 0, 0, 0}} -#endif - -#include "../protocol.h" - -#define MAVLINK_ENABLED_COMMON - -// ENUM DEFINITIONS - - -/** @brief These values define the type of firmware release. These values indicate the first version or release of this type. For example the first alpha release would be 64, the second would be 65. */ -#ifndef HAVE_ENUM_FIRMWARE_VERSION_TYPE -#define HAVE_ENUM_FIRMWARE_VERSION_TYPE -typedef enum FIRMWARE_VERSION_TYPE -{ - FIRMWARE_VERSION_TYPE_DEV=0, /* development release | */ - FIRMWARE_VERSION_TYPE_ALPHA=64, /* alpha release | */ - FIRMWARE_VERSION_TYPE_BETA=128, /* beta release | */ - FIRMWARE_VERSION_TYPE_RC=192, /* release candidate | */ - FIRMWARE_VERSION_TYPE_OFFICIAL=255, /* official stable release | */ - FIRMWARE_VERSION_TYPE_ENUM_END=256, /* | */ -} FIRMWARE_VERSION_TYPE; -#endif - -/** @brief Flags to report failure cases over the high latency telemtry. */ -#ifndef HAVE_ENUM_HL_FAILURE_FLAG -#define HAVE_ENUM_HL_FAILURE_FLAG -typedef enum HL_FAILURE_FLAG -{ - HL_FAILURE_FLAG_GPS=1, /* GPS failure. | */ - HL_FAILURE_FLAG_DIFFERENTIAL_PRESSURE=2, /* Differential pressure sensor failure. | */ - HL_FAILURE_FLAG_ABSOLUTE_PRESSURE=4, /* Absolute pressure sensor failure. | */ - HL_FAILURE_FLAG_3D_ACCEL=8, /* Accelerometer sensor failure. | */ - HL_FAILURE_FLAG_3D_GYRO=16, /* Gyroscope sensor failure. | */ - HL_FAILURE_FLAG_3D_MAG=32, /* Magnetometer sensor failure. | */ - HL_FAILURE_FLAG_TERRAIN=64, /* Terrain subsystem failure. | */ - HL_FAILURE_FLAG_BATTERY=128, /* Battery failure/critical low battery. | */ - HL_FAILURE_FLAG_RC_RECEIVER=256, /* RC receiver failure/no rc connection. | */ - HL_FAILURE_FLAG_OFFBOARD_LINK=512, /* Offboard link failure. | */ - HL_FAILURE_FLAG_ENGINE=1024, /* Engine failure. | */ - HL_FAILURE_FLAG_GEOFENCE=2048, /* Geofence violation. | */ - HL_FAILURE_FLAG_ESTIMATOR=4096, /* Estimator failure, for example measurement rejection or large variances. | */ - HL_FAILURE_FLAG_MISSION=8192, /* Mission failure. | */ - HL_FAILURE_FLAG_ENUM_END=8193, /* | */ -} HL_FAILURE_FLAG; -#endif - -/** @brief Actions that may be specified in MAV_CMD_OVERRIDE_GOTO to override mission execution. */ -#ifndef HAVE_ENUM_MAV_GOTO -#define HAVE_ENUM_MAV_GOTO -typedef enum MAV_GOTO -{ - MAV_GOTO_DO_HOLD=0, /* Hold at the current position. | */ - MAV_GOTO_DO_CONTINUE=1, /* Continue with the next item in mission execution. | */ - MAV_GOTO_HOLD_AT_CURRENT_POSITION=2, /* Hold at the current position of the system | */ - MAV_GOTO_HOLD_AT_SPECIFIED_POSITION=3, /* Hold at the position specified in the parameters of the DO_HOLD action | */ - MAV_GOTO_ENUM_END=4, /* | */ -} MAV_GOTO; -#endif - -/** @brief These defines are predefined OR-combined mode flags. There is no need to use values from this enum, but it - simplifies the use of the mode flags. Note that manual input is enabled in all modes as a safety override. */ -#ifndef HAVE_ENUM_MAV_MODE -#define HAVE_ENUM_MAV_MODE -typedef enum MAV_MODE -{ - MAV_MODE_PREFLIGHT=0, /* System is not ready to fly, booting, calibrating, etc. No flag is set. | */ - MAV_MODE_MANUAL_DISARMED=64, /* System is allowed to be active, under manual (RC) control, no stabilization | */ - MAV_MODE_TEST_DISARMED=66, /* UNDEFINED mode. This solely depends on the autopilot - use with caution, intended for developers only. | */ - MAV_MODE_STABILIZE_DISARMED=80, /* System is allowed to be active, under assisted RC control. | */ - MAV_MODE_GUIDED_DISARMED=88, /* System is allowed to be active, under autonomous control, manual setpoint | */ - MAV_MODE_AUTO_DISARMED=92, /* System is allowed to be active, under autonomous control and navigation (the trajectory is decided onboard and not pre-programmed by waypoints) | */ - MAV_MODE_MANUAL_ARMED=192, /* System is allowed to be active, under manual (RC) control, no stabilization | */ - MAV_MODE_TEST_ARMED=194, /* UNDEFINED mode. This solely depends on the autopilot - use with caution, intended for developers only. | */ - MAV_MODE_STABILIZE_ARMED=208, /* System is allowed to be active, under assisted RC control. | */ - MAV_MODE_GUIDED_ARMED=216, /* System is allowed to be active, under autonomous control, manual setpoint | */ - MAV_MODE_AUTO_ARMED=220, /* System is allowed to be active, under autonomous control and navigation (the trajectory is decided onboard and not pre-programmed by waypoints) | */ - MAV_MODE_ENUM_END=221, /* | */ -} MAV_MODE; -#endif - -/** @brief These encode the sensors whose status is sent as part of the SYS_STATUS message. */ -#ifndef HAVE_ENUM_MAV_SYS_STATUS_SENSOR -#define HAVE_ENUM_MAV_SYS_STATUS_SENSOR -typedef enum MAV_SYS_STATUS_SENSOR -{ - MAV_SYS_STATUS_SENSOR_3D_GYRO=1, /* 0x01 3D gyro | */ - MAV_SYS_STATUS_SENSOR_3D_ACCEL=2, /* 0x02 3D accelerometer | */ - MAV_SYS_STATUS_SENSOR_3D_MAG=4, /* 0x04 3D magnetometer | */ - MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE=8, /* 0x08 absolute pressure | */ - MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE=16, /* 0x10 differential pressure | */ - MAV_SYS_STATUS_SENSOR_GPS=32, /* 0x20 GPS | */ - MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW=64, /* 0x40 optical flow | */ - MAV_SYS_STATUS_SENSOR_VISION_POSITION=128, /* 0x80 computer vision position | */ - MAV_SYS_STATUS_SENSOR_LASER_POSITION=256, /* 0x100 laser based position | */ - MAV_SYS_STATUS_SENSOR_EXTERNAL_GROUND_TRUTH=512, /* 0x200 external ground truth (Vicon or Leica) | */ - MAV_SYS_STATUS_SENSOR_ANGULAR_RATE_CONTROL=1024, /* 0x400 3D angular rate control | */ - MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION=2048, /* 0x800 attitude stabilization | */ - MAV_SYS_STATUS_SENSOR_YAW_POSITION=4096, /* 0x1000 yaw position | */ - MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL=8192, /* 0x2000 z/altitude control | */ - MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL=16384, /* 0x4000 x/y position control | */ - MAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS=32768, /* 0x8000 motor outputs / control | */ - MAV_SYS_STATUS_SENSOR_RC_RECEIVER=65536, /* 0x10000 rc receiver | */ - MAV_SYS_STATUS_SENSOR_3D_GYRO2=131072, /* 0x20000 2nd 3D gyro | */ - MAV_SYS_STATUS_SENSOR_3D_ACCEL2=262144, /* 0x40000 2nd 3D accelerometer | */ - MAV_SYS_STATUS_SENSOR_3D_MAG2=524288, /* 0x80000 2nd 3D magnetometer | */ - MAV_SYS_STATUS_GEOFENCE=1048576, /* 0x100000 geofence | */ - MAV_SYS_STATUS_AHRS=2097152, /* 0x200000 AHRS subsystem health | */ - MAV_SYS_STATUS_TERRAIN=4194304, /* 0x400000 Terrain subsystem health | */ - MAV_SYS_STATUS_REVERSE_MOTOR=8388608, /* 0x800000 Motors are reversed | */ - MAV_SYS_STATUS_LOGGING=16777216, /* 0x1000000 Logging | */ - MAV_SYS_STATUS_SENSOR_BATTERY=33554432, /* 0x2000000 Battery | */ - MAV_SYS_STATUS_SENSOR_PROXIMITY=67108864, /* 0x4000000 Proximity | */ - MAV_SYS_STATUS_SENSOR_SATCOM=134217728, /* 0x8000000 Satellite Communication | */ - MAV_SYS_STATUS_PREARM_CHECK=268435456, /* 0x10000000 pre-arm check status. Always healthy when armed | */ - MAV_SYS_STATUS_OBSTACLE_AVOIDANCE=536870912, /* 0x20000000 Avoidance/collision prevention | */ - MAV_SYS_STATUS_SENSOR_PROPULSION=1073741824, /* 0x40000000 propulsion (actuator, esc, motor or propellor) | */ - MAV_SYS_STATUS_EXTENSION_USED=2147483648, /* 0x80000000 Extended bit-field are used for further sensor status bits (needs to be set in onboard_control_sensors_present only) | */ - MAV_SYS_STATUS_SENSOR_ENUM_END=2147483649, /* | */ -} MAV_SYS_STATUS_SENSOR; -#endif - -/** @brief These encode the sensors whose status is sent as part of the SYS_STATUS message in the extended fields. */ -#ifndef HAVE_ENUM_MAV_SYS_STATUS_SENSOR_EXTENDED -#define HAVE_ENUM_MAV_SYS_STATUS_SENSOR_EXTENDED -typedef enum MAV_SYS_STATUS_SENSOR_EXTENDED -{ - MAV_SYS_STATUS_RECOVERY_SYSTEM=1, /* 0x01 Recovery system (parachute, balloon, retracts etc) | */ - MAV_SYS_STATUS_SENSOR_EXTENDED_ENUM_END=2, /* | */ -} MAV_SYS_STATUS_SENSOR_EXTENDED; -#endif - -/** @brief Coordinate frames used by MAVLink. Not all frames are supported by all commands, messages, or vehicles. - - Global frames use the following naming conventions: - - "GLOBAL": Global coordinate frame with WGS84 latitude/longitude and altitude positive over mean sea level (MSL) by default. - The following modifiers may be used with "GLOBAL": - - "RELATIVE_ALT": Altitude is relative to the vehicle home position rather than MSL. - - "TERRAIN_ALT": Altitude is relative to ground level rather than MSL. - - "INT": Latitude/longitude (in degrees) are scaled by multiplying by 1E7. - - Local frames use the following naming conventions: - - "LOCAL": Origin of local frame is fixed relative to earth. Unless otherwise specified this origin is the origin of the vehicle position-estimator ("EKF"). - - "BODY": Origin of local frame travels with the vehicle. NOTE, "BODY" does NOT indicate alignment of frame axis with vehicle attitude. - - "OFFSET": Deprecated synonym for "BODY" (origin travels with the vehicle). Not to be used for new frames. - - Some deprecated frames do not follow these conventions (e.g. MAV_FRAME_BODY_NED and MAV_FRAME_BODY_OFFSET_NED). - */ -#ifndef HAVE_ENUM_MAV_FRAME -#define HAVE_ENUM_MAV_FRAME -typedef enum MAV_FRAME -{ - MAV_FRAME_GLOBAL=0, /* Global (WGS84) coordinate frame + MSL altitude. First value / x: latitude, second value / y: longitude, third value / z: positive altitude over mean sea level (MSL). | */ - MAV_FRAME_LOCAL_NED=1, /* NED local tangent frame (x: North, y: East, z: Down) with origin fixed relative to earth. | */ - MAV_FRAME_MISSION=2, /* NOT a coordinate frame, indicates a mission command. | */ - MAV_FRAME_GLOBAL_RELATIVE_ALT=3, /* - Global (WGS84) coordinate frame + altitude relative to the home position. - First value / x: latitude, second value / y: longitude, third value / z: positive altitude with 0 being at the altitude of the home position. - | */ - MAV_FRAME_LOCAL_ENU=4, /* ENU local tangent frame (x: East, y: North, z: Up) with origin fixed relative to earth. | */ - MAV_FRAME_GLOBAL_INT=5, /* Global (WGS84) coordinate frame (scaled) + MSL altitude. First value / x: latitude in degrees*1E7, second value / y: longitude in degrees*1E7, third value / z: positive altitude over mean sea level (MSL). | */ - MAV_FRAME_GLOBAL_RELATIVE_ALT_INT=6, /* - Global (WGS84) coordinate frame (scaled) + altitude relative to the home position. - First value / x: latitude in degrees*1E7, second value / y: longitude in degrees*1E7, third value / z: positive altitude with 0 being at the altitude of the home position. - | */ - MAV_FRAME_LOCAL_OFFSET_NED=7, /* NED local tangent frame (x: North, y: East, z: Down) with origin that travels with the vehicle. | */ - MAV_FRAME_BODY_NED=8, /* Same as MAV_FRAME_LOCAL_NED when used to represent position values. Same as MAV_FRAME_BODY_FRD when used with velocity/acceleration values. | */ - MAV_FRAME_BODY_OFFSET_NED=9, /* This is the same as MAV_FRAME_BODY_FRD. | */ - MAV_FRAME_GLOBAL_TERRAIN_ALT=10, /* Global (WGS84) coordinate frame with AGL altitude (at the waypoint coordinate). First value / x: latitude in degrees, second value / y: longitude in degrees, third value / z: positive altitude in meters with 0 being at ground level in terrain model. | */ - MAV_FRAME_GLOBAL_TERRAIN_ALT_INT=11, /* Global (WGS84) coordinate frame (scaled) with AGL altitude (at the waypoint coordinate). First value / x: latitude in degrees*1E7, second value / y: longitude in degrees*1E7, third value / z: positive altitude in meters with 0 being at ground level in terrain model. | */ - MAV_FRAME_BODY_FRD=12, /* FRD local frame aligned to the vehicle's attitude (x: Forward, y: Right, z: Down) with an origin that travels with vehicle. | */ - MAV_FRAME_RESERVED_13=13, /* MAV_FRAME_BODY_FLU - Body fixed frame of reference, Z-up (x: Forward, y: Left, z: Up). | */ - MAV_FRAME_RESERVED_14=14, /* MAV_FRAME_MOCAP_NED - Odometry local coordinate frame of data given by a motion capture system, Z-down (x: North, y: East, z: Down). | */ - MAV_FRAME_RESERVED_15=15, /* MAV_FRAME_MOCAP_ENU - Odometry local coordinate frame of data given by a motion capture system, Z-up (x: East, y: North, z: Up). | */ - MAV_FRAME_RESERVED_16=16, /* MAV_FRAME_VISION_NED - Odometry local coordinate frame of data given by a vision estimation system, Z-down (x: North, y: East, z: Down). | */ - MAV_FRAME_RESERVED_17=17, /* MAV_FRAME_VISION_ENU - Odometry local coordinate frame of data given by a vision estimation system, Z-up (x: East, y: North, z: Up). | */ - MAV_FRAME_RESERVED_18=18, /* MAV_FRAME_ESTIM_NED - Odometry local coordinate frame of data given by an estimator running onboard the vehicle, Z-down (x: North, y: East, z: Down). | */ - MAV_FRAME_RESERVED_19=19, /* MAV_FRAME_ESTIM_ENU - Odometry local coordinate frame of data given by an estimator running onboard the vehicle, Z-up (x: East, y: North, z: Up). | */ - MAV_FRAME_LOCAL_FRD=20, /* FRD local tangent frame (x: Forward, y: Right, z: Down) with origin fixed relative to earth. The forward axis is aligned to the front of the vehicle in the horizontal plane. | */ - MAV_FRAME_LOCAL_FLU=21, /* FLU local tangent frame (x: Forward, y: Left, z: Up) with origin fixed relative to earth. The forward axis is aligned to the front of the vehicle in the horizontal plane. | */ - MAV_FRAME_ENUM_END=22, /* | */ -} MAV_FRAME; -#endif - -/** @brief */ -#ifndef HAVE_ENUM_MAVLINK_DATA_STREAM_TYPE -#define HAVE_ENUM_MAVLINK_DATA_STREAM_TYPE -typedef enum MAVLINK_DATA_STREAM_TYPE -{ - MAVLINK_DATA_STREAM_IMG_JPEG=0, /* | */ - MAVLINK_DATA_STREAM_IMG_BMP=1, /* | */ - MAVLINK_DATA_STREAM_IMG_RAW8U=2, /* | */ - MAVLINK_DATA_STREAM_IMG_RAW32U=3, /* | */ - MAVLINK_DATA_STREAM_IMG_PGM=4, /* | */ - MAVLINK_DATA_STREAM_IMG_PNG=5, /* | */ - MAVLINK_DATA_STREAM_TYPE_ENUM_END=6, /* | */ -} MAVLINK_DATA_STREAM_TYPE; -#endif - -/** @brief Actions following geofence breach. */ -#ifndef HAVE_ENUM_FENCE_ACTION -#define HAVE_ENUM_FENCE_ACTION -typedef enum FENCE_ACTION -{ - FENCE_ACTION_NONE=0, /* Disable fenced mode. If used in a plan this would mean the next fence is disabled. | */ - FENCE_ACTION_GUIDED=1, /* Fly to geofence MAV_CMD_NAV_FENCE_RETURN_POINT in GUIDED mode. Note: This action is only supported by ArduPlane, and may not be supported in all versions. | */ - FENCE_ACTION_REPORT=2, /* Report fence breach, but don't take action | */ - FENCE_ACTION_GUIDED_THR_PASS=3, /* Fly to geofence MAV_CMD_NAV_FENCE_RETURN_POINT with manual throttle control in GUIDED mode. Note: This action is only supported by ArduPlane, and may not be supported in all versions. | */ - FENCE_ACTION_RTL=4, /* Return/RTL mode. | */ - FENCE_ACTION_HOLD=5, /* Hold at current location. | */ - FENCE_ACTION_TERMINATE=6, /* Termination failsafe. Motors are shut down (some flight stacks may trigger other failsafe actions). | */ - FENCE_ACTION_LAND=7, /* Land at current location. | */ - FENCE_ACTION_ENUM_END=8, /* | */ -} FENCE_ACTION; -#endif - -/** @brief */ -#ifndef HAVE_ENUM_FENCE_BREACH -#define HAVE_ENUM_FENCE_BREACH -typedef enum FENCE_BREACH -{ - FENCE_BREACH_NONE=0, /* No last fence breach | */ - FENCE_BREACH_MINALT=1, /* Breached minimum altitude | */ - FENCE_BREACH_MAXALT=2, /* Breached maximum altitude | */ - FENCE_BREACH_BOUNDARY=3, /* Breached fence boundary | */ - FENCE_BREACH_ENUM_END=4, /* | */ -} FENCE_BREACH; -#endif - -/** @brief Actions being taken to mitigate/prevent fence breach */ -#ifndef HAVE_ENUM_FENCE_MITIGATE -#define HAVE_ENUM_FENCE_MITIGATE -typedef enum FENCE_MITIGATE -{ - FENCE_MITIGATE_UNKNOWN=0, /* Unknown | */ - FENCE_MITIGATE_NONE=1, /* No actions being taken | */ - FENCE_MITIGATE_VEL_LIMIT=2, /* Velocity limiting active to prevent breach | */ - FENCE_MITIGATE_ENUM_END=3, /* | */ -} FENCE_MITIGATE; -#endif - -/** @brief Enumeration of possible mount operation modes. This message is used by obsolete/deprecated gimbal messages. */ -#ifndef HAVE_ENUM_MAV_MOUNT_MODE -#define HAVE_ENUM_MAV_MOUNT_MODE -typedef enum MAV_MOUNT_MODE -{ - MAV_MOUNT_MODE_RETRACT=0, /* Load and keep safe position (Roll,Pitch,Yaw) from permant memory and stop stabilization | */ - MAV_MOUNT_MODE_NEUTRAL=1, /* Load and keep neutral position (Roll,Pitch,Yaw) from permanent memory. | */ - MAV_MOUNT_MODE_MAVLINK_TARGETING=2, /* Load neutral position and start MAVLink Roll,Pitch,Yaw control with stabilization | */ - MAV_MOUNT_MODE_RC_TARGETING=3, /* Load neutral position and start RC Roll,Pitch,Yaw control with stabilization | */ - MAV_MOUNT_MODE_GPS_POINT=4, /* Load neutral position and start to point to Lat,Lon,Alt | */ - MAV_MOUNT_MODE_SYSID_TARGET=5, /* Gimbal tracks system with specified system ID | */ - MAV_MOUNT_MODE_HOME_LOCATION=6, /* Gimbal tracks home position | */ - MAV_MOUNT_MODE_ENUM_END=7, /* | */ -} MAV_MOUNT_MODE; -#endif - -/** @brief Gimbal device (low level) capability flags (bitmap). */ -#ifndef HAVE_ENUM_GIMBAL_DEVICE_CAP_FLAGS -#define HAVE_ENUM_GIMBAL_DEVICE_CAP_FLAGS -typedef enum GIMBAL_DEVICE_CAP_FLAGS -{ - GIMBAL_DEVICE_CAP_FLAGS_HAS_RETRACT=1, /* Gimbal device supports a retracted position. | */ - GIMBAL_DEVICE_CAP_FLAGS_HAS_NEUTRAL=2, /* Gimbal device supports a horizontal, forward looking position, stabilized. | */ - GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_AXIS=4, /* Gimbal device supports rotating around roll axis. | */ - GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_FOLLOW=8, /* Gimbal device supports to follow a roll angle relative to the vehicle. | */ - GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_LOCK=16, /* Gimbal device supports locking to a roll angle (generally that's the default with roll stabilized). | */ - GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_AXIS=32, /* Gimbal device supports rotating around pitch axis. | */ - GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_FOLLOW=64, /* Gimbal device supports to follow a pitch angle relative to the vehicle. | */ - GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_LOCK=128, /* Gimbal device supports locking to a pitch angle (generally that's the default with pitch stabilized). | */ - GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_AXIS=256, /* Gimbal device supports rotating around yaw axis. | */ - GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_FOLLOW=512, /* Gimbal device supports to follow a yaw angle relative to the vehicle (generally that's the default). | */ - GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_LOCK=1024, /* Gimbal device supports locking to an absolute heading, i.e., yaw angle relative to North (earth frame, often this is an option available). | */ - GIMBAL_DEVICE_CAP_FLAGS_SUPPORTS_INFINITE_YAW=2048, /* Gimbal device supports yawing/panning infinetely (e.g. using slip disk). | */ - GIMBAL_DEVICE_CAP_FLAGS_SUPPORTS_YAW_IN_EARTH_FRAME=4096, /* Gimbal device supports yaw angles and angular velocities relative to North (earth frame). This usually requires support by an autopilot via AUTOPILOT_STATE_FOR_GIMBAL_DEVICE. Support can go on and off during runtime, which is reported by the flag GIMBAL_DEVICE_FLAGS_CAN_ACCEPT_YAW_IN_EARTH_FRAME. | */ - GIMBAL_DEVICE_CAP_FLAGS_HAS_RC_INPUTS=8192, /* Gimbal device supports radio control inputs as an alternative input for controlling the gimbal orientation. | */ - GIMBAL_DEVICE_CAP_FLAGS_ENUM_END=8193, /* | */ -} GIMBAL_DEVICE_CAP_FLAGS; -#endif - -/** @brief Gimbal manager high level capability flags (bitmap). The first 16 bits are identical to the GIMBAL_DEVICE_CAP_FLAGS. However, the gimbal manager does not need to copy the flags from the gimbal but can also enhance the capabilities and thus add flags. */ -#ifndef HAVE_ENUM_GIMBAL_MANAGER_CAP_FLAGS -#define HAVE_ENUM_GIMBAL_MANAGER_CAP_FLAGS -typedef enum GIMBAL_MANAGER_CAP_FLAGS -{ - GIMBAL_MANAGER_CAP_FLAGS_HAS_RETRACT=1, /* Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_RETRACT. | */ - GIMBAL_MANAGER_CAP_FLAGS_HAS_NEUTRAL=2, /* Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_NEUTRAL. | */ - GIMBAL_MANAGER_CAP_FLAGS_HAS_ROLL_AXIS=4, /* Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_AXIS. | */ - GIMBAL_MANAGER_CAP_FLAGS_HAS_ROLL_FOLLOW=8, /* Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_FOLLOW. | */ - GIMBAL_MANAGER_CAP_FLAGS_HAS_ROLL_LOCK=16, /* Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_LOCK. | */ - GIMBAL_MANAGER_CAP_FLAGS_HAS_PITCH_AXIS=32, /* Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_AXIS. | */ - GIMBAL_MANAGER_CAP_FLAGS_HAS_PITCH_FOLLOW=64, /* Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_FOLLOW. | */ - GIMBAL_MANAGER_CAP_FLAGS_HAS_PITCH_LOCK=128, /* Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_LOCK. | */ - GIMBAL_MANAGER_CAP_FLAGS_HAS_YAW_AXIS=256, /* Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_AXIS. | */ - GIMBAL_MANAGER_CAP_FLAGS_HAS_YAW_FOLLOW=512, /* Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_FOLLOW. | */ - GIMBAL_MANAGER_CAP_FLAGS_HAS_YAW_LOCK=1024, /* Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_LOCK. | */ - GIMBAL_MANAGER_CAP_FLAGS_SUPPORTS_INFINITE_YAW=2048, /* Based on GIMBAL_DEVICE_CAP_FLAGS_SUPPORTS_INFINITE_YAW. | */ - GIMBAL_MANAGER_CAP_FLAGS_SUPPORTS_YAW_IN_EARTH_FRAME=4096, /* Based on GIMBAL_DEVICE_CAP_FLAGS_SUPPORTS_YAW_IN_EARTH_FRAME. | */ - GIMBAL_MANAGER_CAP_FLAGS_HAS_RC_INPUTS=8192, /* Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_RC_INPUTS. | */ - GIMBAL_MANAGER_CAP_FLAGS_CAN_POINT_LOCATION_LOCAL=65536, /* Gimbal manager supports to point to a local position. | */ - GIMBAL_MANAGER_CAP_FLAGS_CAN_POINT_LOCATION_GLOBAL=131072, /* Gimbal manager supports to point to a global latitude, longitude, altitude position. | */ - GIMBAL_MANAGER_CAP_FLAGS_ENUM_END=131073, /* | */ -} GIMBAL_MANAGER_CAP_FLAGS; -#endif - -/** @brief Flags for gimbal device (lower level) operation. */ -#ifndef HAVE_ENUM_GIMBAL_DEVICE_FLAGS -#define HAVE_ENUM_GIMBAL_DEVICE_FLAGS -typedef enum GIMBAL_DEVICE_FLAGS -{ - GIMBAL_DEVICE_FLAGS_RETRACT=1, /* Set to retracted safe position (no stabilization), takes presedence over all other flags. | */ - GIMBAL_DEVICE_FLAGS_NEUTRAL=2, /* Set to neutral/default position, taking precedence over all other flags except RETRACT. Neutral is commonly forward-facing and horizontal (roll=pitch=yaw=0) but may be any orientation. | */ - GIMBAL_DEVICE_FLAGS_ROLL_LOCK=4, /* Lock roll angle to absolute angle relative to horizon (not relative to vehicle). This is generally the default with a stabilizing gimbal. | */ - GIMBAL_DEVICE_FLAGS_PITCH_LOCK=8, /* Lock pitch angle to absolute angle relative to horizon (not relative to vehicle). This is generally the default with a stabilizing gimbal. | */ - GIMBAL_DEVICE_FLAGS_YAW_LOCK=16, /* Lock yaw angle to absolute angle relative to North (not relative to vehicle). If this flag is set, the yaw angle and z component of angular velocity are relative to North (earth frame, x-axis pointing North), else they are relative to the vehicle heading (vehicle frame, earth frame rotated so that the x-axis is pointing forward). | */ - GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME=32, /* Yaw angle and z component of angular velocity are relative to the vehicle heading (vehicle frame, earth frame rotated such that the x-axis is pointing forward). | */ - GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME=64, /* Yaw angle and z component of angular velocity are relative to North (earth frame, x-axis is pointing North). | */ - GIMBAL_DEVICE_FLAGS_ACCEPTS_YAW_IN_EARTH_FRAME=128, /* Gimbal device can accept yaw angle inputs relative to North (earth frame). This flag is only for reporting (attempts to set this flag are ignored). | */ - GIMBAL_DEVICE_FLAGS_RC_EXCLUSIVE=256, /* The gimbal orientation is set exclusively by the RC signals feed to the gimbal's radio control inputs. MAVLink messages for setting the gimbal orientation (GIMBAL_DEVICE_SET_ATTITUDE) are ignored. | */ - GIMBAL_DEVICE_FLAGS_RC_MIXED=512, /* The gimbal orientation is determined by combining/mixing the RC signals feed to the gimbal's radio control inputs and the MAVLink messages for setting the gimbal orientation (GIMBAL_DEVICE_SET_ATTITUDE). How these two controls are combined or mixed is not defined by the protocol but is up to the implementation. | */ - GIMBAL_DEVICE_FLAGS_ENUM_END=513, /* | */ -} GIMBAL_DEVICE_FLAGS; -#endif - -/** @brief Flags for high level gimbal manager operation The first 16 bits are identical to the GIMBAL_DEVICE_FLAGS. */ -#ifndef HAVE_ENUM_GIMBAL_MANAGER_FLAGS -#define HAVE_ENUM_GIMBAL_MANAGER_FLAGS -typedef enum GIMBAL_MANAGER_FLAGS -{ - GIMBAL_MANAGER_FLAGS_RETRACT=1, /* Based on GIMBAL_DEVICE_FLAGS_RETRACT. | */ - GIMBAL_MANAGER_FLAGS_NEUTRAL=2, /* Based on GIMBAL_DEVICE_FLAGS_NEUTRAL. | */ - GIMBAL_MANAGER_FLAGS_ROLL_LOCK=4, /* Based on GIMBAL_DEVICE_FLAGS_ROLL_LOCK. | */ - GIMBAL_MANAGER_FLAGS_PITCH_LOCK=8, /* Based on GIMBAL_DEVICE_FLAGS_PITCH_LOCK. | */ - GIMBAL_MANAGER_FLAGS_YAW_LOCK=16, /* Based on GIMBAL_DEVICE_FLAGS_YAW_LOCK. | */ - GIMBAL_MANAGER_FLAGS_YAW_IN_VEHICLE_FRAME=32, /* Based on GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME. | */ - GIMBAL_MANAGER_FLAGS_YAW_IN_EARTH_FRAME=64, /* Based on GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME. | */ - GIMBAL_MANAGER_FLAGS_ACCEPTS_YAW_IN_EARTH_FRAME=128, /* Based on GIMBAL_DEVICE_FLAGS_ACCEPTS_YAW_IN_EARTH_FRAME. | */ - GIMBAL_MANAGER_FLAGS_RC_EXCLUSIVE=256, /* Based on GIMBAL_DEVICE_FLAGS_RC_EXCLUSIVE. | */ - GIMBAL_MANAGER_FLAGS_RC_MIXED=512, /* Based on GIMBAL_DEVICE_FLAGS_RC_MIXED. | */ - GIMBAL_MANAGER_FLAGS_ENUM_END=513, /* | */ -} GIMBAL_MANAGER_FLAGS; -#endif - -/** @brief Gimbal device (low level) error flags (bitmap, 0 means no error) */ -#ifndef HAVE_ENUM_GIMBAL_DEVICE_ERROR_FLAGS -#define HAVE_ENUM_GIMBAL_DEVICE_ERROR_FLAGS -typedef enum GIMBAL_DEVICE_ERROR_FLAGS -{ - GIMBAL_DEVICE_ERROR_FLAGS_AT_ROLL_LIMIT=1, /* Gimbal device is limited by hardware roll limit. | */ - GIMBAL_DEVICE_ERROR_FLAGS_AT_PITCH_LIMIT=2, /* Gimbal device is limited by hardware pitch limit. | */ - GIMBAL_DEVICE_ERROR_FLAGS_AT_YAW_LIMIT=4, /* Gimbal device is limited by hardware yaw limit. | */ - GIMBAL_DEVICE_ERROR_FLAGS_ENCODER_ERROR=8, /* There is an error with the gimbal encoders. | */ - GIMBAL_DEVICE_ERROR_FLAGS_POWER_ERROR=16, /* There is an error with the gimbal power source. | */ - GIMBAL_DEVICE_ERROR_FLAGS_MOTOR_ERROR=32, /* There is an error with the gimbal motors. | */ - GIMBAL_DEVICE_ERROR_FLAGS_SOFTWARE_ERROR=64, /* There is an error with the gimbal's software. | */ - GIMBAL_DEVICE_ERROR_FLAGS_COMMS_ERROR=128, /* There is an error with the gimbal's communication. | */ - GIMBAL_DEVICE_ERROR_FLAGS_CALIBRATION_RUNNING=256, /* Gimbal device is currently calibrating. | */ - GIMBAL_DEVICE_ERROR_FLAGS_NO_MANAGER=512, /* Gimbal device is not assigned to a gimbal manager. | */ - GIMBAL_DEVICE_ERROR_FLAGS_ENUM_END=513, /* | */ -} GIMBAL_DEVICE_ERROR_FLAGS; -#endif - -/** @brief Gripper actions. */ -#ifndef HAVE_ENUM_GRIPPER_ACTIONS -#define HAVE_ENUM_GRIPPER_ACTIONS -typedef enum GRIPPER_ACTIONS -{ - GRIPPER_ACTION_RELEASE=0, /* Gripper release cargo. | */ - GRIPPER_ACTION_GRAB=1, /* Gripper grab onto cargo. | */ - GRIPPER_ACTIONS_ENUM_END=2, /* | */ -} GRIPPER_ACTIONS; -#endif - -/** @brief Winch actions. */ -#ifndef HAVE_ENUM_WINCH_ACTIONS -#define HAVE_ENUM_WINCH_ACTIONS -typedef enum WINCH_ACTIONS -{ - WINCH_RELAXED=0, /* Allow motor to freewheel. | */ - WINCH_RELATIVE_LENGTH_CONTROL=1, /* Wind or unwind specified length of line, optionally using specified rate. | */ - WINCH_RATE_CONTROL=2, /* Wind or unwind line at specified rate. | */ - WINCH_LOCK=3, /* Perform the locking sequence to relieve motor while in the fully retracted position. Only action and instance command parameters are used, others are ignored. | */ - WINCH_DELIVER=4, /* Sequence of drop, slow down, touch down, reel up, lock. Only action and instance command parameters are used, others are ignored. | */ - WINCH_HOLD=5, /* Engage motor and hold current position. Only action and instance command parameters are used, others are ignored. | */ - WINCH_RETRACT=6, /* Return the reel to the fully retracted position. Only action and instance command parameters are used, others are ignored. | */ - WINCH_LOAD_LINE=7, /* Load the reel with line. The winch will calculate the total loaded length and stop when the tension exceeds a threshold. Only action and instance command parameters are used, others are ignored. | */ - WINCH_ABANDON_LINE=8, /* Spool out the entire length of the line. Only action and instance command parameters are used, others are ignored. | */ - WINCH_LOAD_PAYLOAD=9, /* Spools out just enough to present the hook to the user to load the payload. Only action and instance command parameters are used, others are ignored | */ - WINCH_ACTIONS_ENUM_END=10, /* | */ -} WINCH_ACTIONS; -#endif - -/** @brief Generalized UAVCAN node health */ -#ifndef HAVE_ENUM_UAVCAN_NODE_HEALTH -#define HAVE_ENUM_UAVCAN_NODE_HEALTH -typedef enum UAVCAN_NODE_HEALTH -{ - UAVCAN_NODE_HEALTH_OK=0, /* The node is functioning properly. | */ - UAVCAN_NODE_HEALTH_WARNING=1, /* A critical parameter went out of range or the node has encountered a minor failure. | */ - UAVCAN_NODE_HEALTH_ERROR=2, /* The node has encountered a major failure. | */ - UAVCAN_NODE_HEALTH_CRITICAL=3, /* The node has suffered a fatal malfunction. | */ - UAVCAN_NODE_HEALTH_ENUM_END=4, /* | */ -} UAVCAN_NODE_HEALTH; -#endif - -/** @brief Generalized UAVCAN node mode */ -#ifndef HAVE_ENUM_UAVCAN_NODE_MODE -#define HAVE_ENUM_UAVCAN_NODE_MODE -typedef enum UAVCAN_NODE_MODE -{ - UAVCAN_NODE_MODE_OPERATIONAL=0, /* The node is performing its primary functions. | */ - UAVCAN_NODE_MODE_INITIALIZATION=1, /* The node is initializing; this mode is entered immediately after startup. | */ - UAVCAN_NODE_MODE_MAINTENANCE=2, /* The node is under maintenance. | */ - UAVCAN_NODE_MODE_SOFTWARE_UPDATE=3, /* The node is in the process of updating its software. | */ - UAVCAN_NODE_MODE_OFFLINE=7, /* The node is no longer available online. | */ - UAVCAN_NODE_MODE_ENUM_END=8, /* | */ -} UAVCAN_NODE_MODE; -#endif - -/** @brief Indicates the ESC connection type. */ -#ifndef HAVE_ENUM_ESC_CONNECTION_TYPE -#define HAVE_ENUM_ESC_CONNECTION_TYPE -typedef enum ESC_CONNECTION_TYPE -{ - ESC_CONNECTION_TYPE_PPM=0, /* Traditional PPM ESC. | */ - ESC_CONNECTION_TYPE_SERIAL=1, /* Serial Bus connected ESC. | */ - ESC_CONNECTION_TYPE_ONESHOT=2, /* One Shot PPM ESC. | */ - ESC_CONNECTION_TYPE_I2C=3, /* I2C ESC. | */ - ESC_CONNECTION_TYPE_CAN=4, /* CAN-Bus ESC. | */ - ESC_CONNECTION_TYPE_DSHOT=5, /* DShot ESC. | */ - ESC_CONNECTION_TYPE_ENUM_END=6, /* | */ -} ESC_CONNECTION_TYPE; -#endif - -/** @brief Flags to report ESC failures. */ -#ifndef HAVE_ENUM_ESC_FAILURE_FLAGS -#define HAVE_ENUM_ESC_FAILURE_FLAGS -typedef enum ESC_FAILURE_FLAGS -{ - ESC_FAILURE_NONE=0, /* No ESC failure. | */ - ESC_FAILURE_OVER_CURRENT=1, /* Over current failure. | */ - ESC_FAILURE_OVER_VOLTAGE=2, /* Over voltage failure. | */ - ESC_FAILURE_OVER_TEMPERATURE=4, /* Over temperature failure. | */ - ESC_FAILURE_OVER_RPM=8, /* Over RPM failure. | */ - ESC_FAILURE_INCONSISTENT_CMD=16, /* Inconsistent command failure i.e. out of bounds. | */ - ESC_FAILURE_MOTOR_STUCK=32, /* Motor stuck failure. | */ - ESC_FAILURE_GENERIC=64, /* Generic ESC failure. | */ - ESC_FAILURE_FLAGS_ENUM_END=65, /* | */ -} ESC_FAILURE_FLAGS; -#endif - -/** @brief Flags to indicate the status of camera storage. */ -#ifndef HAVE_ENUM_STORAGE_STATUS -#define HAVE_ENUM_STORAGE_STATUS -typedef enum STORAGE_STATUS -{ - STORAGE_STATUS_EMPTY=0, /* Storage is missing (no microSD card loaded for example.) | */ - STORAGE_STATUS_UNFORMATTED=1, /* Storage present but unformatted. | */ - STORAGE_STATUS_READY=2, /* Storage present and ready. | */ - STORAGE_STATUS_NOT_SUPPORTED=3, /* Camera does not supply storage status information. Capacity information in STORAGE_INFORMATION fields will be ignored. | */ - STORAGE_STATUS_ENUM_END=4, /* | */ -} STORAGE_STATUS; -#endif - -/** @brief Flags to indicate the type of storage. */ -#ifndef HAVE_ENUM_STORAGE_TYPE -#define HAVE_ENUM_STORAGE_TYPE -typedef enum STORAGE_TYPE -{ - STORAGE_TYPE_UNKNOWN=0, /* Storage type is not known. | */ - STORAGE_TYPE_USB_STICK=1, /* Storage type is USB device. | */ - STORAGE_TYPE_SD=2, /* Storage type is SD card. | */ - STORAGE_TYPE_MICROSD=3, /* Storage type is microSD card. | */ - STORAGE_TYPE_CF=4, /* Storage type is CFast. | */ - STORAGE_TYPE_CFE=5, /* Storage type is CFexpress. | */ - STORAGE_TYPE_XQD=6, /* Storage type is XQD. | */ - STORAGE_TYPE_HD=7, /* Storage type is HD mass storage type. | */ - STORAGE_TYPE_OTHER=254, /* Storage type is other, not listed type. | */ - STORAGE_TYPE_ENUM_END=255, /* | */ -} STORAGE_TYPE; -#endif - -/** @brief Flags to indicate usage for a particular storage (see STORAGE_INFORMATION.storage_usage and MAV_CMD_SET_STORAGE_USAGE). */ -#ifndef HAVE_ENUM_STORAGE_USAGE_FLAG -#define HAVE_ENUM_STORAGE_USAGE_FLAG -typedef enum STORAGE_USAGE_FLAG -{ - STORAGE_USAGE_FLAG_SET=1, /* Always set to 1 (indicates STORAGE_INFORMATION.storage_usage is supported). | */ - STORAGE_USAGE_FLAG_PHOTO=2, /* Storage for saving photos. | */ - STORAGE_USAGE_FLAG_VIDEO=4, /* Storage for saving videos. | */ - STORAGE_USAGE_FLAG_LOGS=8, /* Storage for saving logs. | */ - STORAGE_USAGE_FLAG_ENUM_END=9, /* | */ -} STORAGE_USAGE_FLAG; -#endif - -/** @brief Yaw behaviour during orbit flight. */ -#ifndef HAVE_ENUM_ORBIT_YAW_BEHAVIOUR -#define HAVE_ENUM_ORBIT_YAW_BEHAVIOUR -typedef enum ORBIT_YAW_BEHAVIOUR -{ - ORBIT_YAW_BEHAVIOUR_HOLD_FRONT_TO_CIRCLE_CENTER=0, /* Vehicle front points to the center (default). | */ - ORBIT_YAW_BEHAVIOUR_HOLD_INITIAL_HEADING=1, /* Vehicle front holds heading when message received. | */ - ORBIT_YAW_BEHAVIOUR_UNCONTROLLED=2, /* Yaw uncontrolled. | */ - ORBIT_YAW_BEHAVIOUR_HOLD_FRONT_TANGENT_TO_CIRCLE=3, /* Vehicle front follows flight path (tangential to circle). | */ - ORBIT_YAW_BEHAVIOUR_RC_CONTROLLED=4, /* Yaw controlled by RC input. | */ - ORBIT_YAW_BEHAVIOUR_ENUM_END=5, /* | */ -} ORBIT_YAW_BEHAVIOUR; -#endif - -/** @brief Possible responses from a WIFI_CONFIG_AP message. */ -#ifndef HAVE_ENUM_WIFI_CONFIG_AP_RESPONSE -#define HAVE_ENUM_WIFI_CONFIG_AP_RESPONSE -typedef enum WIFI_CONFIG_AP_RESPONSE -{ - WIFI_CONFIG_AP_RESPONSE_UNDEFINED=0, /* Undefined response. Likely an indicative of a system that doesn't support this request. | */ - WIFI_CONFIG_AP_RESPONSE_ACCEPTED=1, /* Changes accepted. | */ - WIFI_CONFIG_AP_RESPONSE_REJECTED=2, /* Changes rejected. | */ - WIFI_CONFIG_AP_RESPONSE_MODE_ERROR=3, /* Invalid Mode. | */ - WIFI_CONFIG_AP_RESPONSE_SSID_ERROR=4, /* Invalid SSID. | */ - WIFI_CONFIG_AP_RESPONSE_PASSWORD_ERROR=5, /* Invalid Password. | */ - WIFI_CONFIG_AP_RESPONSE_ENUM_END=6, /* | */ -} WIFI_CONFIG_AP_RESPONSE; -#endif - -/** @brief Possible responses from a CELLULAR_CONFIG message. */ -#ifndef HAVE_ENUM_CELLULAR_CONFIG_RESPONSE -#define HAVE_ENUM_CELLULAR_CONFIG_RESPONSE -typedef enum CELLULAR_CONFIG_RESPONSE -{ - CELLULAR_CONFIG_RESPONSE_ACCEPTED=0, /* Changes accepted. | */ - CELLULAR_CONFIG_RESPONSE_APN_ERROR=1, /* Invalid APN. | */ - CELLULAR_CONFIG_RESPONSE_PIN_ERROR=2, /* Invalid PIN. | */ - CELLULAR_CONFIG_RESPONSE_REJECTED=3, /* Changes rejected. | */ - CELLULAR_CONFIG_BLOCKED_PUK_REQUIRED=4, /* PUK is required to unblock SIM card. | */ - CELLULAR_CONFIG_RESPONSE_ENUM_END=5, /* | */ -} CELLULAR_CONFIG_RESPONSE; -#endif - -/** @brief WiFi Mode. */ -#ifndef HAVE_ENUM_WIFI_CONFIG_AP_MODE -#define HAVE_ENUM_WIFI_CONFIG_AP_MODE -typedef enum WIFI_CONFIG_AP_MODE -{ - WIFI_CONFIG_AP_MODE_UNDEFINED=0, /* WiFi mode is undefined. | */ - WIFI_CONFIG_AP_MODE_AP=1, /* WiFi configured as an access point. | */ - WIFI_CONFIG_AP_MODE_STATION=2, /* WiFi configured as a station connected to an existing local WiFi network. | */ - WIFI_CONFIG_AP_MODE_DISABLED=3, /* WiFi disabled. | */ - WIFI_CONFIG_AP_MODE_ENUM_END=4, /* | */ -} WIFI_CONFIG_AP_MODE; -#endif - -/** @brief Supported component metadata types. These are used in the "general" metadata file returned by COMPONENT_METADATA to provide information about supported metadata types. The types are not used directly in MAVLink messages. */ -#ifndef HAVE_ENUM_COMP_METADATA_TYPE -#define HAVE_ENUM_COMP_METADATA_TYPE -typedef enum COMP_METADATA_TYPE -{ - COMP_METADATA_TYPE_GENERAL=0, /* General information about the component. General metadata includes information about other metadata types supported by the component. Files of this type must be supported, and must be downloadable from vehicle using a MAVLink FTP URI. | */ - COMP_METADATA_TYPE_PARAMETER=1, /* Parameter meta data. | */ - COMP_METADATA_TYPE_COMMANDS=2, /* Meta data that specifies which commands and command parameters the vehicle supports. (WIP) | */ - COMP_METADATA_TYPE_PERIPHERALS=3, /* Meta data that specifies external non-MAVLink peripherals. | */ - COMP_METADATA_TYPE_EVENTS=4, /* Meta data for the events interface. | */ - COMP_METADATA_TYPE_ACTUATORS=5, /* Meta data for actuator configuration (motors, servos and vehicle geometry) and testing. | */ - COMP_METADATA_TYPE_ENUM_END=6, /* | */ -} COMP_METADATA_TYPE; -#endif - -/** @brief Actuator configuration, used to change a setting on an actuator. Component information metadata can be used to know which outputs support which commands. */ -#ifndef HAVE_ENUM_ACTUATOR_CONFIGURATION -#define HAVE_ENUM_ACTUATOR_CONFIGURATION -typedef enum ACTUATOR_CONFIGURATION -{ - ACTUATOR_CONFIGURATION_NONE=0, /* Do nothing. | */ - ACTUATOR_CONFIGURATION_BEEP=1, /* Command the actuator to beep now. | */ - ACTUATOR_CONFIGURATION_3D_MODE_ON=2, /* Permanently set the actuator (ESC) to 3D mode (reversible thrust). | */ - ACTUATOR_CONFIGURATION_3D_MODE_OFF=3, /* Permanently set the actuator (ESC) to non 3D mode (non-reversible thrust). | */ - ACTUATOR_CONFIGURATION_SPIN_DIRECTION1=4, /* Permanently set the actuator (ESC) to spin direction 1 (which can be clockwise or counter-clockwise). | */ - ACTUATOR_CONFIGURATION_SPIN_DIRECTION2=5, /* Permanently set the actuator (ESC) to spin direction 2 (opposite of direction 1). | */ - ACTUATOR_CONFIGURATION_ENUM_END=6, /* | */ -} ACTUATOR_CONFIGURATION; -#endif - -/** @brief Actuator output function. Values greater or equal to 1000 are autopilot-specific. */ -#ifndef HAVE_ENUM_ACTUATOR_OUTPUT_FUNCTION -#define HAVE_ENUM_ACTUATOR_OUTPUT_FUNCTION -typedef enum ACTUATOR_OUTPUT_FUNCTION -{ - ACTUATOR_OUTPUT_FUNCTION_NONE=0, /* No function (disabled). | */ - ACTUATOR_OUTPUT_FUNCTION_MOTOR1=1, /* Motor 1 | */ - ACTUATOR_OUTPUT_FUNCTION_MOTOR2=2, /* Motor 2 | */ - ACTUATOR_OUTPUT_FUNCTION_MOTOR3=3, /* Motor 3 | */ - ACTUATOR_OUTPUT_FUNCTION_MOTOR4=4, /* Motor 4 | */ - ACTUATOR_OUTPUT_FUNCTION_MOTOR5=5, /* Motor 5 | */ - ACTUATOR_OUTPUT_FUNCTION_MOTOR6=6, /* Motor 6 | */ - ACTUATOR_OUTPUT_FUNCTION_MOTOR7=7, /* Motor 7 | */ - ACTUATOR_OUTPUT_FUNCTION_MOTOR8=8, /* Motor 8 | */ - ACTUATOR_OUTPUT_FUNCTION_MOTOR9=9, /* Motor 9 | */ - ACTUATOR_OUTPUT_FUNCTION_MOTOR10=10, /* Motor 10 | */ - ACTUATOR_OUTPUT_FUNCTION_MOTOR11=11, /* Motor 11 | */ - ACTUATOR_OUTPUT_FUNCTION_MOTOR12=12, /* Motor 12 | */ - ACTUATOR_OUTPUT_FUNCTION_MOTOR13=13, /* Motor 13 | */ - ACTUATOR_OUTPUT_FUNCTION_MOTOR14=14, /* Motor 14 | */ - ACTUATOR_OUTPUT_FUNCTION_MOTOR15=15, /* Motor 15 | */ - ACTUATOR_OUTPUT_FUNCTION_MOTOR16=16, /* Motor 16 | */ - ACTUATOR_OUTPUT_FUNCTION_SERVO1=33, /* Servo 1 | */ - ACTUATOR_OUTPUT_FUNCTION_SERVO2=34, /* Servo 2 | */ - ACTUATOR_OUTPUT_FUNCTION_SERVO3=35, /* Servo 3 | */ - ACTUATOR_OUTPUT_FUNCTION_SERVO4=36, /* Servo 4 | */ - ACTUATOR_OUTPUT_FUNCTION_SERVO5=37, /* Servo 5 | */ - ACTUATOR_OUTPUT_FUNCTION_SERVO6=38, /* Servo 6 | */ - ACTUATOR_OUTPUT_FUNCTION_SERVO7=39, /* Servo 7 | */ - ACTUATOR_OUTPUT_FUNCTION_SERVO8=40, /* Servo 8 | */ - ACTUATOR_OUTPUT_FUNCTION_SERVO9=41, /* Servo 9 | */ - ACTUATOR_OUTPUT_FUNCTION_SERVO10=42, /* Servo 10 | */ - ACTUATOR_OUTPUT_FUNCTION_SERVO11=43, /* Servo 11 | */ - ACTUATOR_OUTPUT_FUNCTION_SERVO12=44, /* Servo 12 | */ - ACTUATOR_OUTPUT_FUNCTION_SERVO13=45, /* Servo 13 | */ - ACTUATOR_OUTPUT_FUNCTION_SERVO14=46, /* Servo 14 | */ - ACTUATOR_OUTPUT_FUNCTION_SERVO15=47, /* Servo 15 | */ - ACTUATOR_OUTPUT_FUNCTION_SERVO16=48, /* Servo 16 | */ - ACTUATOR_OUTPUT_FUNCTION_ENUM_END=49, /* | */ -} ACTUATOR_OUTPUT_FUNCTION; -#endif - -/** @brief Enable axes that will be tuned via autotuning. Used in MAV_CMD_DO_AUTOTUNE_ENABLE. */ -#ifndef HAVE_ENUM_AUTOTUNE_AXIS -#define HAVE_ENUM_AUTOTUNE_AXIS -typedef enum AUTOTUNE_AXIS -{ - AUTOTUNE_AXIS_DEFAULT=0, /* Flight stack tunes axis according to its default settings. | */ - AUTOTUNE_AXIS_ROLL=1, /* Autotune roll axis. | */ - AUTOTUNE_AXIS_PITCH=2, /* Autotune pitch axis. | */ - AUTOTUNE_AXIS_YAW=4, /* Autotune yaw axis. | */ - AUTOTUNE_AXIS_ENUM_END=5, /* | */ -} AUTOTUNE_AXIS; -#endif - -/** @brief - Actions for reading/writing parameters between persistent and volatile storage when using MAV_CMD_PREFLIGHT_STORAGE. - (Commonly parameters are loaded from persistent storage (flash/EEPROM) into volatile storage (RAM) on startup and written back when they are changed.) - */ -#ifndef HAVE_ENUM_PREFLIGHT_STORAGE_PARAMETER_ACTION -#define HAVE_ENUM_PREFLIGHT_STORAGE_PARAMETER_ACTION -typedef enum PREFLIGHT_STORAGE_PARAMETER_ACTION -{ - PARAM_READ_PERSISTENT=0, /* Read all parameters from persistent storage. Replaces values in volatile storage. | */ - PARAM_WRITE_PERSISTENT=1, /* Write all parameter values to persistent storage (flash/EEPROM) | */ - PARAM_RESET_CONFIG_DEFAULT=2, /* Reset all user configurable parameters to their default value (including airframe selection, sensor calibration data, safety settings, and so on). Does not reset values that contain operation counters and vehicle computed statistics. | */ - PARAM_RESET_SENSOR_DEFAULT=3, /* Reset only sensor calibration parameters to factory defaults (or firmware default if not available) | */ - PARAM_RESET_ALL_DEFAULT=4, /* Reset all parameters, including operation counters, to default values | */ - PREFLIGHT_STORAGE_PARAMETER_ACTION_ENUM_END=5, /* | */ -} PREFLIGHT_STORAGE_PARAMETER_ACTION; -#endif - -/** @brief - Actions for reading and writing plan information (mission, rally points, geofence) between persistent and volatile storage when using MAV_CMD_PREFLIGHT_STORAGE. - (Commonly missions are loaded from persistent storage (flash/EEPROM) into volatile storage (RAM) on startup and written back when they are changed.) - */ -#ifndef HAVE_ENUM_PREFLIGHT_STORAGE_MISSION_ACTION -#define HAVE_ENUM_PREFLIGHT_STORAGE_MISSION_ACTION -typedef enum PREFLIGHT_STORAGE_MISSION_ACTION -{ - MISSION_READ_PERSISTENT=0, /* Read current mission data from persistent storage | */ - MISSION_WRITE_PERSISTENT=1, /* Write current mission data to persistent storage | */ - MISSION_RESET_DEFAULT=2, /* Erase all mission data stored on the vehicle (both persistent and volatile storage) | */ - PREFLIGHT_STORAGE_MISSION_ACTION_ENUM_END=3, /* | */ -} PREFLIGHT_STORAGE_MISSION_ACTION; -#endif - -/** @brief A data stream is not a fixed set of messages, but rather a - recommendation to the autopilot software. Individual autopilots may or may not obey - the recommended messages. */ -#ifndef HAVE_ENUM_MAV_DATA_STREAM -#define HAVE_ENUM_MAV_DATA_STREAM -typedef enum MAV_DATA_STREAM -{ - MAV_DATA_STREAM_ALL=0, /* Enable all data streams | */ - MAV_DATA_STREAM_RAW_SENSORS=1, /* Enable IMU_RAW, GPS_RAW, GPS_STATUS packets. | */ - MAV_DATA_STREAM_EXTENDED_STATUS=2, /* Enable GPS_STATUS, CONTROL_STATUS, AUX_STATUS | */ - MAV_DATA_STREAM_RC_CHANNELS=3, /* Enable RC_CHANNELS_SCALED, RC_CHANNELS_RAW, SERVO_OUTPUT_RAW | */ - MAV_DATA_STREAM_RAW_CONTROLLER=4, /* Enable ATTITUDE_CONTROLLER_OUTPUT, POSITION_CONTROLLER_OUTPUT, NAV_CONTROLLER_OUTPUT. | */ - MAV_DATA_STREAM_POSITION=6, /* Enable LOCAL_POSITION, GLOBAL_POSITION_INT messages. | */ - MAV_DATA_STREAM_EXTRA1=10, /* Dependent on the autopilot | */ - MAV_DATA_STREAM_EXTRA2=11, /* Dependent on the autopilot | */ - MAV_DATA_STREAM_EXTRA3=12, /* Dependent on the autopilot | */ - MAV_DATA_STREAM_ENUM_END=13, /* | */ -} MAV_DATA_STREAM; -#endif - -/** @brief The ROI (region of interest) for the vehicle. This can be - be used by the vehicle for camera/vehicle attitude alignment (see - MAV_CMD_NAV_ROI). */ -#ifndef HAVE_ENUM_MAV_ROI -#define HAVE_ENUM_MAV_ROI -typedef enum MAV_ROI -{ - MAV_ROI_NONE=0, /* No region of interest. | */ - MAV_ROI_WPNEXT=1, /* Point toward next waypoint, with optional pitch/roll/yaw offset. | */ - MAV_ROI_WPINDEX=2, /* Point toward given waypoint. | */ - MAV_ROI_LOCATION=3, /* Point toward fixed location. | */ - MAV_ROI_TARGET=4, /* Point toward of given id. | */ - MAV_ROI_ENUM_END=5, /* | */ -} MAV_ROI; -#endif - -/** @brief Specifies the datatype of a MAVLink parameter. */ -#ifndef HAVE_ENUM_MAV_PARAM_TYPE -#define HAVE_ENUM_MAV_PARAM_TYPE -typedef enum MAV_PARAM_TYPE -{ - MAV_PARAM_TYPE_UINT8=1, /* 8-bit unsigned integer | */ - MAV_PARAM_TYPE_INT8=2, /* 8-bit signed integer | */ - MAV_PARAM_TYPE_UINT16=3, /* 16-bit unsigned integer | */ - MAV_PARAM_TYPE_INT16=4, /* 16-bit signed integer | */ - MAV_PARAM_TYPE_UINT32=5, /* 32-bit unsigned integer | */ - MAV_PARAM_TYPE_INT32=6, /* 32-bit signed integer | */ - MAV_PARAM_TYPE_UINT64=7, /* 64-bit unsigned integer | */ - MAV_PARAM_TYPE_INT64=8, /* 64-bit signed integer | */ - MAV_PARAM_TYPE_REAL32=9, /* 32-bit floating-point | */ - MAV_PARAM_TYPE_REAL64=10, /* 64-bit floating-point | */ - MAV_PARAM_TYPE_ENUM_END=11, /* | */ -} MAV_PARAM_TYPE; -#endif - -/** @brief Specifies the datatype of a MAVLink extended parameter. */ -#ifndef HAVE_ENUM_MAV_PARAM_EXT_TYPE -#define HAVE_ENUM_MAV_PARAM_EXT_TYPE -typedef enum MAV_PARAM_EXT_TYPE -{ - MAV_PARAM_EXT_TYPE_UINT8=1, /* 8-bit unsigned integer | */ - MAV_PARAM_EXT_TYPE_INT8=2, /* 8-bit signed integer | */ - MAV_PARAM_EXT_TYPE_UINT16=3, /* 16-bit unsigned integer | */ - MAV_PARAM_EXT_TYPE_INT16=4, /* 16-bit signed integer | */ - MAV_PARAM_EXT_TYPE_UINT32=5, /* 32-bit unsigned integer | */ - MAV_PARAM_EXT_TYPE_INT32=6, /* 32-bit signed integer | */ - MAV_PARAM_EXT_TYPE_UINT64=7, /* 64-bit unsigned integer | */ - MAV_PARAM_EXT_TYPE_INT64=8, /* 64-bit signed integer | */ - MAV_PARAM_EXT_TYPE_REAL32=9, /* 32-bit floating-point | */ - MAV_PARAM_EXT_TYPE_REAL64=10, /* 64-bit floating-point | */ - MAV_PARAM_EXT_TYPE_CUSTOM=11, /* Custom Type | */ - MAV_PARAM_EXT_TYPE_ENUM_END=12, /* | */ -} MAV_PARAM_EXT_TYPE; -#endif - -/** @brief Result from a MAVLink command (MAV_CMD) */ -#ifndef HAVE_ENUM_MAV_RESULT -#define HAVE_ENUM_MAV_RESULT -typedef enum MAV_RESULT -{ - MAV_RESULT_ACCEPTED=0, /* Command is valid (is supported and has valid parameters), and was executed. | */ - MAV_RESULT_TEMPORARILY_REJECTED=1, /* Command is valid, but cannot be executed at this time. This is used to indicate a problem that should be fixed just by waiting (e.g. a state machine is busy, can't arm because have not got GPS lock, etc.). Retrying later should work. | */ - MAV_RESULT_DENIED=2, /* Command is invalid (is supported but has invalid parameters). Retrying same command and parameters will not work. | */ - MAV_RESULT_UNSUPPORTED=3, /* Command is not supported (unknown). | */ - MAV_RESULT_FAILED=4, /* Command is valid, but execution has failed. This is used to indicate any non-temporary or unexpected problem, i.e. any problem that must be fixed before the command can succeed/be retried. For example, attempting to write a file when out of memory, attempting to arm when sensors are not calibrated, etc. | */ - MAV_RESULT_IN_PROGRESS=5, /* Command is valid and is being executed. This will be followed by further progress updates, i.e. the component may send further COMMAND_ACK messages with result MAV_RESULT_IN_PROGRESS (at a rate decided by the implementation), and must terminate by sending a COMMAND_ACK message with final result of the operation. The COMMAND_ACK.progress field can be used to indicate the progress of the operation. | */ - MAV_RESULT_CANCELLED=6, /* Command has been cancelled (as a result of receiving a COMMAND_CANCEL message). | */ - MAV_RESULT_COMMAND_LONG_ONLY=7, /* Command is valid, but it is only accepted when sent as a COMMAND_LONG (as it has float values for params 5 and 6). | */ - MAV_RESULT_COMMAND_INT_ONLY=8, /* Command is valid, but it is only accepted when sent as a COMMAND_INT (as it encodes a location in params 5, 6 and 7, and hence requires a reference MAV_FRAME). | */ - MAV_RESULT_COMMAND_UNSUPPORTED_MAV_FRAME=9, /* Command is invalid because a frame is required and the specified frame is not supported. | */ - MAV_RESULT_ENUM_END=10, /* | */ -} MAV_RESULT; -#endif - -/** @brief Result of mission operation (in a MISSION_ACK message). */ -#ifndef HAVE_ENUM_MAV_MISSION_RESULT -#define HAVE_ENUM_MAV_MISSION_RESULT -typedef enum MAV_MISSION_RESULT -{ - MAV_MISSION_ACCEPTED=0, /* mission accepted OK | */ - MAV_MISSION_ERROR=1, /* Generic error / not accepting mission commands at all right now. | */ - MAV_MISSION_UNSUPPORTED_FRAME=2, /* Coordinate frame is not supported. | */ - MAV_MISSION_UNSUPPORTED=3, /* Command is not supported. | */ - MAV_MISSION_NO_SPACE=4, /* Mission items exceed storage space. | */ - MAV_MISSION_INVALID=5, /* One of the parameters has an invalid value. | */ - MAV_MISSION_INVALID_PARAM1=6, /* param1 has an invalid value. | */ - MAV_MISSION_INVALID_PARAM2=7, /* param2 has an invalid value. | */ - MAV_MISSION_INVALID_PARAM3=8, /* param3 has an invalid value. | */ - MAV_MISSION_INVALID_PARAM4=9, /* param4 has an invalid value. | */ - MAV_MISSION_INVALID_PARAM5_X=10, /* x / param5 has an invalid value. | */ - MAV_MISSION_INVALID_PARAM6_Y=11, /* y / param6 has an invalid value. | */ - MAV_MISSION_INVALID_PARAM7=12, /* z / param7 has an invalid value. | */ - MAV_MISSION_INVALID_SEQUENCE=13, /* Mission item received out of sequence | */ - MAV_MISSION_DENIED=14, /* Not accepting any mission commands from this communication partner. | */ - MAV_MISSION_OPERATION_CANCELLED=15, /* Current mission operation cancelled (e.g. mission upload, mission download). | */ - MAV_MISSION_RESULT_ENUM_END=16, /* | */ -} MAV_MISSION_RESULT; -#endif - -/** @brief Indicates the severity level, generally used for status messages to indicate their relative urgency. Based on RFC-5424 using expanded definitions at: http://www.kiwisyslog.com/kb/info:-syslog-message-levels/. */ -#ifndef HAVE_ENUM_MAV_SEVERITY -#define HAVE_ENUM_MAV_SEVERITY -typedef enum MAV_SEVERITY -{ - MAV_SEVERITY_EMERGENCY=0, /* System is unusable. This is a "panic" condition. | */ - MAV_SEVERITY_ALERT=1, /* Action should be taken immediately. Indicates error in non-critical systems. | */ - MAV_SEVERITY_CRITICAL=2, /* Action must be taken immediately. Indicates failure in a primary system. | */ - MAV_SEVERITY_ERROR=3, /* Indicates an error in secondary/redundant systems. | */ - MAV_SEVERITY_WARNING=4, /* Indicates about a possible future error if this is not resolved within a given timeframe. Example would be a low battery warning. | */ - MAV_SEVERITY_NOTICE=5, /* An unusual event has occurred, though not an error condition. This should be investigated for the root cause. | */ - MAV_SEVERITY_INFO=6, /* Normal operational messages. Useful for logging. No action is required for these messages. | */ - MAV_SEVERITY_DEBUG=7, /* Useful non-operational messages that can assist in debugging. These should not occur during normal operation. | */ - MAV_SEVERITY_ENUM_END=8, /* | */ -} MAV_SEVERITY; -#endif - -/** @brief Power supply status flags (bitmask) */ -#ifndef HAVE_ENUM_MAV_POWER_STATUS -#define HAVE_ENUM_MAV_POWER_STATUS -typedef enum MAV_POWER_STATUS -{ - MAV_POWER_STATUS_BRICK_VALID=1, /* main brick power supply valid | */ - MAV_POWER_STATUS_SERVO_VALID=2, /* main servo power supply valid for FMU | */ - MAV_POWER_STATUS_USB_CONNECTED=4, /* USB power is connected | */ - MAV_POWER_STATUS_PERIPH_OVERCURRENT=8, /* peripheral supply is in over-current state | */ - MAV_POWER_STATUS_PERIPH_HIPOWER_OVERCURRENT=16, /* hi-power peripheral supply is in over-current state | */ - MAV_POWER_STATUS_CHANGED=32, /* Power status has changed since boot | */ - MAV_POWER_STATUS_ENUM_END=33, /* | */ -} MAV_POWER_STATUS; -#endif - -/** @brief SERIAL_CONTROL device types */ -#ifndef HAVE_ENUM_SERIAL_CONTROL_DEV -#define HAVE_ENUM_SERIAL_CONTROL_DEV -typedef enum SERIAL_CONTROL_DEV -{ - SERIAL_CONTROL_DEV_TELEM1=0, /* First telemetry port | */ - SERIAL_CONTROL_DEV_TELEM2=1, /* Second telemetry port | */ - SERIAL_CONTROL_DEV_GPS1=2, /* First GPS port | */ - SERIAL_CONTROL_DEV_GPS2=3, /* Second GPS port | */ - SERIAL_CONTROL_DEV_SHELL=10, /* system shell | */ - SERIAL_CONTROL_SERIAL0=100, /* SERIAL0 | */ - SERIAL_CONTROL_SERIAL1=101, /* SERIAL1 | */ - SERIAL_CONTROL_SERIAL2=102, /* SERIAL2 | */ - SERIAL_CONTROL_SERIAL3=103, /* SERIAL3 | */ - SERIAL_CONTROL_SERIAL4=104, /* SERIAL4 | */ - SERIAL_CONTROL_SERIAL5=105, /* SERIAL5 | */ - SERIAL_CONTROL_SERIAL6=106, /* SERIAL6 | */ - SERIAL_CONTROL_SERIAL7=107, /* SERIAL7 | */ - SERIAL_CONTROL_SERIAL8=108, /* SERIAL8 | */ - SERIAL_CONTROL_SERIAL9=109, /* SERIAL9 | */ - SERIAL_CONTROL_DEV_ENUM_END=110, /* | */ -} SERIAL_CONTROL_DEV; -#endif - -/** @brief SERIAL_CONTROL flags (bitmask) */ -#ifndef HAVE_ENUM_SERIAL_CONTROL_FLAG -#define HAVE_ENUM_SERIAL_CONTROL_FLAG -typedef enum SERIAL_CONTROL_FLAG -{ - SERIAL_CONTROL_FLAG_REPLY=1, /* Set if this is a reply | */ - SERIAL_CONTROL_FLAG_RESPOND=2, /* Set if the sender wants the receiver to send a response as another SERIAL_CONTROL message | */ - SERIAL_CONTROL_FLAG_EXCLUSIVE=4, /* Set if access to the serial port should be removed from whatever driver is currently using it, giving exclusive access to the SERIAL_CONTROL protocol. The port can be handed back by sending a request without this flag set | */ - SERIAL_CONTROL_FLAG_BLOCKING=8, /* Block on writes to the serial port | */ - SERIAL_CONTROL_FLAG_MULTI=16, /* Send multiple replies until port is drained | */ - SERIAL_CONTROL_FLAG_ENUM_END=17, /* | */ -} SERIAL_CONTROL_FLAG; -#endif - -/** @brief Enumeration of distance sensor types */ -#ifndef HAVE_ENUM_MAV_DISTANCE_SENSOR -#define HAVE_ENUM_MAV_DISTANCE_SENSOR -typedef enum MAV_DISTANCE_SENSOR -{ - MAV_DISTANCE_SENSOR_LASER=0, /* Laser rangefinder, e.g. LightWare SF02/F or PulsedLight units | */ - MAV_DISTANCE_SENSOR_ULTRASOUND=1, /* Ultrasound rangefinder, e.g. MaxBotix units | */ - MAV_DISTANCE_SENSOR_INFRARED=2, /* Infrared rangefinder, e.g. Sharp units | */ - MAV_DISTANCE_SENSOR_RADAR=3, /* Radar type, e.g. uLanding units | */ - MAV_DISTANCE_SENSOR_UNKNOWN=4, /* Broken or unknown type, e.g. analog units | */ - MAV_DISTANCE_SENSOR_ENUM_END=5, /* | */ -} MAV_DISTANCE_SENSOR; -#endif - -/** @brief Enumeration of sensor orientation, according to its rotations */ -#ifndef HAVE_ENUM_MAV_SENSOR_ORIENTATION -#define HAVE_ENUM_MAV_SENSOR_ORIENTATION -typedef enum MAV_SENSOR_ORIENTATION -{ - MAV_SENSOR_ROTATION_NONE=0, /* Roll: 0, Pitch: 0, Yaw: 0 | */ - MAV_SENSOR_ROTATION_YAW_45=1, /* Roll: 0, Pitch: 0, Yaw: 45 | */ - MAV_SENSOR_ROTATION_YAW_90=2, /* Roll: 0, Pitch: 0, Yaw: 90 | */ - MAV_SENSOR_ROTATION_YAW_135=3, /* Roll: 0, Pitch: 0, Yaw: 135 | */ - MAV_SENSOR_ROTATION_YAW_180=4, /* Roll: 0, Pitch: 0, Yaw: 180 | */ - MAV_SENSOR_ROTATION_YAW_225=5, /* Roll: 0, Pitch: 0, Yaw: 225 | */ - MAV_SENSOR_ROTATION_YAW_270=6, /* Roll: 0, Pitch: 0, Yaw: 270 | */ - MAV_SENSOR_ROTATION_YAW_315=7, /* Roll: 0, Pitch: 0, Yaw: 315 | */ - MAV_SENSOR_ROTATION_ROLL_180=8, /* Roll: 180, Pitch: 0, Yaw: 0 | */ - MAV_SENSOR_ROTATION_ROLL_180_YAW_45=9, /* Roll: 180, Pitch: 0, Yaw: 45 | */ - MAV_SENSOR_ROTATION_ROLL_180_YAW_90=10, /* Roll: 180, Pitch: 0, Yaw: 90 | */ - MAV_SENSOR_ROTATION_ROLL_180_YAW_135=11, /* Roll: 180, Pitch: 0, Yaw: 135 | */ - MAV_SENSOR_ROTATION_PITCH_180=12, /* Roll: 0, Pitch: 180, Yaw: 0 | */ - MAV_SENSOR_ROTATION_ROLL_180_YAW_225=13, /* Roll: 180, Pitch: 0, Yaw: 225 | */ - MAV_SENSOR_ROTATION_ROLL_180_YAW_270=14, /* Roll: 180, Pitch: 0, Yaw: 270 | */ - MAV_SENSOR_ROTATION_ROLL_180_YAW_315=15, /* Roll: 180, Pitch: 0, Yaw: 315 | */ - MAV_SENSOR_ROTATION_ROLL_90=16, /* Roll: 90, Pitch: 0, Yaw: 0 | */ - MAV_SENSOR_ROTATION_ROLL_90_YAW_45=17, /* Roll: 90, Pitch: 0, Yaw: 45 | */ - MAV_SENSOR_ROTATION_ROLL_90_YAW_90=18, /* Roll: 90, Pitch: 0, Yaw: 90 | */ - MAV_SENSOR_ROTATION_ROLL_90_YAW_135=19, /* Roll: 90, Pitch: 0, Yaw: 135 | */ - MAV_SENSOR_ROTATION_ROLL_270=20, /* Roll: 270, Pitch: 0, Yaw: 0 | */ - MAV_SENSOR_ROTATION_ROLL_270_YAW_45=21, /* Roll: 270, Pitch: 0, Yaw: 45 | */ - MAV_SENSOR_ROTATION_ROLL_270_YAW_90=22, /* Roll: 270, Pitch: 0, Yaw: 90 | */ - MAV_SENSOR_ROTATION_ROLL_270_YAW_135=23, /* Roll: 270, Pitch: 0, Yaw: 135 | */ - MAV_SENSOR_ROTATION_PITCH_90=24, /* Roll: 0, Pitch: 90, Yaw: 0 | */ - MAV_SENSOR_ROTATION_PITCH_270=25, /* Roll: 0, Pitch: 270, Yaw: 0 | */ - MAV_SENSOR_ROTATION_PITCH_180_YAW_90=26, /* Roll: 0, Pitch: 180, Yaw: 90 | */ - MAV_SENSOR_ROTATION_PITCH_180_YAW_270=27, /* Roll: 0, Pitch: 180, Yaw: 270 | */ - MAV_SENSOR_ROTATION_ROLL_90_PITCH_90=28, /* Roll: 90, Pitch: 90, Yaw: 0 | */ - MAV_SENSOR_ROTATION_ROLL_180_PITCH_90=29, /* Roll: 180, Pitch: 90, Yaw: 0 | */ - MAV_SENSOR_ROTATION_ROLL_270_PITCH_90=30, /* Roll: 270, Pitch: 90, Yaw: 0 | */ - MAV_SENSOR_ROTATION_ROLL_90_PITCH_180=31, /* Roll: 90, Pitch: 180, Yaw: 0 | */ - MAV_SENSOR_ROTATION_ROLL_270_PITCH_180=32, /* Roll: 270, Pitch: 180, Yaw: 0 | */ - MAV_SENSOR_ROTATION_ROLL_90_PITCH_270=33, /* Roll: 90, Pitch: 270, Yaw: 0 | */ - MAV_SENSOR_ROTATION_ROLL_180_PITCH_270=34, /* Roll: 180, Pitch: 270, Yaw: 0 | */ - MAV_SENSOR_ROTATION_ROLL_270_PITCH_270=35, /* Roll: 270, Pitch: 270, Yaw: 0 | */ - MAV_SENSOR_ROTATION_ROLL_90_PITCH_180_YAW_90=36, /* Roll: 90, Pitch: 180, Yaw: 90 | */ - MAV_SENSOR_ROTATION_ROLL_90_YAW_270=37, /* Roll: 90, Pitch: 0, Yaw: 270 | */ - MAV_SENSOR_ROTATION_ROLL_90_PITCH_68_YAW_293=38, /* Roll: 90, Pitch: 68, Yaw: 293 | */ - MAV_SENSOR_ROTATION_PITCH_315=39, /* Pitch: 315 | */ - MAV_SENSOR_ROTATION_ROLL_90_PITCH_315=40, /* Roll: 90, Pitch: 315 | */ - MAV_SENSOR_ROTATION_CUSTOM=100, /* Custom orientation | */ - MAV_SENSOR_ORIENTATION_ENUM_END=101, /* | */ -} MAV_SENSOR_ORIENTATION; -#endif - -/** @brief Bitmask of (optional) autopilot capabilities (64 bit). If a bit is set, the autopilot supports this capability. */ -#ifndef HAVE_ENUM_MAV_PROTOCOL_CAPABILITY -#define HAVE_ENUM_MAV_PROTOCOL_CAPABILITY -typedef enum MAV_PROTOCOL_CAPABILITY -{ - MAV_PROTOCOL_CAPABILITY_MISSION_FLOAT=1, /* Autopilot supports the MISSION_ITEM float message type. - Note that MISSION_ITEM is deprecated, and autopilots should use MISSION_INT instead. - | */ - MAV_PROTOCOL_CAPABILITY_PARAM_FLOAT=2, /* Autopilot supports the new param float message type. | */ - MAV_PROTOCOL_CAPABILITY_MISSION_INT=4, /* Autopilot supports MISSION_ITEM_INT scaled integer message type. - Note that this flag must always be set if missions are supported, because missions must always use MISSION_ITEM_INT (rather than MISSION_ITEM, which is deprecated). - | */ - MAV_PROTOCOL_CAPABILITY_COMMAND_INT=8, /* Autopilot supports COMMAND_INT scaled integer message type. | */ - MAV_PROTOCOL_CAPABILITY_PARAM_ENCODE_BYTEWISE=16, /* Parameter protocol uses byte-wise encoding of parameter values into param_value (float) fields: https://mavlink.io/en/services/parameter.html#parameter-encoding. - Note that either this flag or MAV_PROTOCOL_CAPABILITY_PARAM_ENCODE_C_CAST should be set if the parameter protocol is supported. - | */ - MAV_PROTOCOL_CAPABILITY_FTP=32, /* Autopilot supports the File Transfer Protocol v1: https://mavlink.io/en/services/ftp.html. | */ - MAV_PROTOCOL_CAPABILITY_SET_ATTITUDE_TARGET=64, /* Autopilot supports commanding attitude offboard. | */ - MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_LOCAL_NED=128, /* Autopilot supports commanding position and velocity targets in local NED frame. | */ - MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_GLOBAL_INT=256, /* Autopilot supports commanding position and velocity targets in global scaled integers. | */ - MAV_PROTOCOL_CAPABILITY_TERRAIN=512, /* Autopilot supports terrain protocol / data handling. | */ - MAV_PROTOCOL_CAPABILITY_RESERVED3=1024, /* Reserved for future use. | */ - MAV_PROTOCOL_CAPABILITY_FLIGHT_TERMINATION=2048, /* Autopilot supports the MAV_CMD_DO_FLIGHTTERMINATION command (flight termination). | */ - MAV_PROTOCOL_CAPABILITY_COMPASS_CALIBRATION=4096, /* Autopilot supports onboard compass calibration. | */ - MAV_PROTOCOL_CAPABILITY_MAVLINK2=8192, /* Autopilot supports MAVLink version 2. | */ - MAV_PROTOCOL_CAPABILITY_MISSION_FENCE=16384, /* Autopilot supports mission fence protocol. | */ - MAV_PROTOCOL_CAPABILITY_MISSION_RALLY=32768, /* Autopilot supports mission rally point protocol. | */ - MAV_PROTOCOL_CAPABILITY_RESERVED2=65536, /* Reserved for future use. | */ - MAV_PROTOCOL_CAPABILITY_PARAM_ENCODE_C_CAST=131072, /* Parameter protocol uses C-cast of parameter values to set the param_value (float) fields: https://mavlink.io/en/services/parameter.html#parameter-encoding. - Note that either this flag or MAV_PROTOCOL_CAPABILITY_PARAM_ENCODE_BYTEWISE should be set if the parameter protocol is supported. - | */ - MAV_PROTOCOL_CAPABILITY_ENUM_END=131073, /* | */ -} MAV_PROTOCOL_CAPABILITY; -#endif - -/** @brief Type of mission items being requested/sent in mission protocol. */ -#ifndef HAVE_ENUM_MAV_MISSION_TYPE -#define HAVE_ENUM_MAV_MISSION_TYPE -typedef enum MAV_MISSION_TYPE -{ - MAV_MISSION_TYPE_MISSION=0, /* Items are mission commands for main mission. | */ - MAV_MISSION_TYPE_FENCE=1, /* Specifies GeoFence area(s). Items are MAV_CMD_NAV_FENCE_ GeoFence items. | */ - MAV_MISSION_TYPE_RALLY=2, /* Specifies the rally points for the vehicle. Rally points are alternative RTL points. Items are MAV_CMD_NAV_RALLY_POINT rally point items. | */ - MAV_MISSION_TYPE_ALL=255, /* Only used in MISSION_CLEAR_ALL to clear all mission types. | */ - MAV_MISSION_TYPE_ENUM_END=256, /* | */ -} MAV_MISSION_TYPE; -#endif - -/** @brief Enumeration of estimator types */ -#ifndef HAVE_ENUM_MAV_ESTIMATOR_TYPE -#define HAVE_ENUM_MAV_ESTIMATOR_TYPE -typedef enum MAV_ESTIMATOR_TYPE -{ - MAV_ESTIMATOR_TYPE_UNKNOWN=0, /* Unknown type of the estimator. | */ - MAV_ESTIMATOR_TYPE_NAIVE=1, /* This is a naive estimator without any real covariance feedback. | */ - MAV_ESTIMATOR_TYPE_VISION=2, /* Computer vision based estimate. Might be up to scale. | */ - MAV_ESTIMATOR_TYPE_VIO=3, /* Visual-inertial estimate. | */ - MAV_ESTIMATOR_TYPE_GPS=4, /* Plain GPS estimate. | */ - MAV_ESTIMATOR_TYPE_GPS_INS=5, /* Estimator integrating GPS and inertial sensing. | */ - MAV_ESTIMATOR_TYPE_MOCAP=6, /* Estimate from external motion capturing system. | */ - MAV_ESTIMATOR_TYPE_LIDAR=7, /* Estimator based on lidar sensor input. | */ - MAV_ESTIMATOR_TYPE_AUTOPILOT=8, /* Estimator on autopilot. | */ - MAV_ESTIMATOR_TYPE_ENUM_END=9, /* | */ -} MAV_ESTIMATOR_TYPE; -#endif - -/** @brief Enumeration of battery types */ -#ifndef HAVE_ENUM_MAV_BATTERY_TYPE -#define HAVE_ENUM_MAV_BATTERY_TYPE -typedef enum MAV_BATTERY_TYPE -{ - MAV_BATTERY_TYPE_UNKNOWN=0, /* Not specified. | */ - MAV_BATTERY_TYPE_LIPO=1, /* Lithium polymer battery | */ - MAV_BATTERY_TYPE_LIFE=2, /* Lithium-iron-phosphate battery | */ - MAV_BATTERY_TYPE_LION=3, /* Lithium-ION battery | */ - MAV_BATTERY_TYPE_NIMH=4, /* Nickel metal hydride battery | */ - MAV_BATTERY_TYPE_ENUM_END=5, /* | */ -} MAV_BATTERY_TYPE; -#endif - -/** @brief Enumeration of battery functions */ -#ifndef HAVE_ENUM_MAV_BATTERY_FUNCTION -#define HAVE_ENUM_MAV_BATTERY_FUNCTION -typedef enum MAV_BATTERY_FUNCTION -{ - MAV_BATTERY_FUNCTION_UNKNOWN=0, /* Battery function is unknown | */ - MAV_BATTERY_FUNCTION_ALL=1, /* Battery supports all flight systems | */ - MAV_BATTERY_FUNCTION_PROPULSION=2, /* Battery for the propulsion system | */ - MAV_BATTERY_FUNCTION_AVIONICS=3, /* Avionics battery | */ - MAV_BATTERY_FUNCTION_PAYLOAD=4, /* Payload battery | */ - MAV_BATTERY_FUNCTION_ENUM_END=5, /* | */ -} MAV_BATTERY_FUNCTION; -#endif - -/** @brief Enumeration for battery charge states. */ -#ifndef HAVE_ENUM_MAV_BATTERY_CHARGE_STATE -#define HAVE_ENUM_MAV_BATTERY_CHARGE_STATE -typedef enum MAV_BATTERY_CHARGE_STATE -{ - MAV_BATTERY_CHARGE_STATE_UNDEFINED=0, /* Low battery state is not provided | */ - MAV_BATTERY_CHARGE_STATE_OK=1, /* Battery is not in low state. Normal operation. | */ - MAV_BATTERY_CHARGE_STATE_LOW=2, /* Battery state is low, warn and monitor close. | */ - MAV_BATTERY_CHARGE_STATE_CRITICAL=3, /* Battery state is critical, return or abort immediately. | */ - MAV_BATTERY_CHARGE_STATE_EMERGENCY=4, /* Battery state is too low for ordinary abort sequence. Perform fastest possible emergency stop to prevent damage. | */ - MAV_BATTERY_CHARGE_STATE_FAILED=5, /* Battery failed, damage unavoidable. Possible causes (faults) are listed in MAV_BATTERY_FAULT. | */ - MAV_BATTERY_CHARGE_STATE_UNHEALTHY=6, /* Battery is diagnosed to be defective or an error occurred, usage is discouraged / prohibited. Possible causes (faults) are listed in MAV_BATTERY_FAULT. | */ - MAV_BATTERY_CHARGE_STATE_CHARGING=7, /* Battery is charging. | */ - MAV_BATTERY_CHARGE_STATE_ENUM_END=8, /* | */ -} MAV_BATTERY_CHARGE_STATE; -#endif - -/** @brief Battery mode. Note, the normal operation mode (i.e. when flying) should be reported as MAV_BATTERY_MODE_UNKNOWN to allow message trimming in normal flight. */ -#ifndef HAVE_ENUM_MAV_BATTERY_MODE -#define HAVE_ENUM_MAV_BATTERY_MODE -typedef enum MAV_BATTERY_MODE -{ - MAV_BATTERY_MODE_UNKNOWN=0, /* Battery mode not supported/unknown battery mode/normal operation. | */ - MAV_BATTERY_MODE_AUTO_DISCHARGING=1, /* Battery is auto discharging (towards storage level). | */ - MAV_BATTERY_MODE_HOT_SWAP=2, /* Battery in hot-swap mode (current limited to prevent spikes that might damage sensitive electrical circuits). | */ - MAV_BATTERY_MODE_ENUM_END=3, /* | */ -} MAV_BATTERY_MODE; -#endif - -/** @brief Smart battery supply status/fault flags (bitmask) for health indication. The battery must also report either MAV_BATTERY_CHARGE_STATE_FAILED or MAV_BATTERY_CHARGE_STATE_UNHEALTHY if any of these are set. */ -#ifndef HAVE_ENUM_MAV_BATTERY_FAULT -#define HAVE_ENUM_MAV_BATTERY_FAULT -typedef enum MAV_BATTERY_FAULT -{ - MAV_BATTERY_FAULT_DEEP_DISCHARGE=1, /* Battery has deep discharged. | */ - MAV_BATTERY_FAULT_SPIKES=2, /* Voltage spikes. | */ - MAV_BATTERY_FAULT_CELL_FAIL=4, /* One or more cells have failed. Battery should also report MAV_BATTERY_CHARGE_STATE_FAILE (and should not be used). | */ - MAV_BATTERY_FAULT_OVER_CURRENT=8, /* Over-current fault. | */ - MAV_BATTERY_FAULT_OVER_TEMPERATURE=16, /* Over-temperature fault. | */ - MAV_BATTERY_FAULT_UNDER_TEMPERATURE=32, /* Under-temperature fault. | */ - MAV_BATTERY_FAULT_INCOMPATIBLE_VOLTAGE=64, /* Vehicle voltage is not compatible with this battery (batteries on same power rail should have similar voltage). | */ - MAV_BATTERY_FAULT_INCOMPATIBLE_FIRMWARE=128, /* Battery firmware is not compatible with current autopilot firmware. | */ - BATTERY_FAULT_INCOMPATIBLE_CELLS_CONFIGURATION=256, /* Battery is not compatible due to cell configuration (e.g. 5s1p when vehicle requires 6s). | */ - MAV_BATTERY_FAULT_ENUM_END=257, /* | */ -} MAV_BATTERY_FAULT; -#endif - -/** @brief Flags to report status/failure cases for a power generator (used in GENERATOR_STATUS). Note that FAULTS are conditions that cause the generator to fail. Warnings are conditions that require attention before the next use (they indicate the system is not operating properly). */ -#ifndef HAVE_ENUM_MAV_GENERATOR_STATUS_FLAG -#define HAVE_ENUM_MAV_GENERATOR_STATUS_FLAG -typedef enum MAV_GENERATOR_STATUS_FLAG -{ - MAV_GENERATOR_STATUS_FLAG_OFF=1, /* Generator is off. | */ - MAV_GENERATOR_STATUS_FLAG_READY=2, /* Generator is ready to start generating power. | */ - MAV_GENERATOR_STATUS_FLAG_GENERATING=4, /* Generator is generating power. | */ - MAV_GENERATOR_STATUS_FLAG_CHARGING=8, /* Generator is charging the batteries (generating enough power to charge and provide the load). | */ - MAV_GENERATOR_STATUS_FLAG_REDUCED_POWER=16, /* Generator is operating at a reduced maximum power. | */ - MAV_GENERATOR_STATUS_FLAG_MAXPOWER=32, /* Generator is providing the maximum output. | */ - MAV_GENERATOR_STATUS_FLAG_OVERTEMP_WARNING=64, /* Generator is near the maximum operating temperature, cooling is insufficient. | */ - MAV_GENERATOR_STATUS_FLAG_OVERTEMP_FAULT=128, /* Generator hit the maximum operating temperature and shutdown. | */ - MAV_GENERATOR_STATUS_FLAG_ELECTRONICS_OVERTEMP_WARNING=256, /* Power electronics are near the maximum operating temperature, cooling is insufficient. | */ - MAV_GENERATOR_STATUS_FLAG_ELECTRONICS_OVERTEMP_FAULT=512, /* Power electronics hit the maximum operating temperature and shutdown. | */ - MAV_GENERATOR_STATUS_FLAG_ELECTRONICS_FAULT=1024, /* Power electronics experienced a fault and shutdown. | */ - MAV_GENERATOR_STATUS_FLAG_POWERSOURCE_FAULT=2048, /* The power source supplying the generator failed e.g. mechanical generator stopped, tether is no longer providing power, solar cell is in shade, hydrogen reaction no longer happening. | */ - MAV_GENERATOR_STATUS_FLAG_COMMUNICATION_WARNING=4096, /* Generator controller having communication problems. | */ - MAV_GENERATOR_STATUS_FLAG_COOLING_WARNING=8192, /* Power electronic or generator cooling system error. | */ - MAV_GENERATOR_STATUS_FLAG_POWER_RAIL_FAULT=16384, /* Generator controller power rail experienced a fault. | */ - MAV_GENERATOR_STATUS_FLAG_OVERCURRENT_FAULT=32768, /* Generator controller exceeded the overcurrent threshold and shutdown to prevent damage. | */ - MAV_GENERATOR_STATUS_FLAG_BATTERY_OVERCHARGE_CURRENT_FAULT=65536, /* Generator controller detected a high current going into the batteries and shutdown to prevent battery damage. | */ - MAV_GENERATOR_STATUS_FLAG_OVERVOLTAGE_FAULT=131072, /* Generator controller exceeded it's overvoltage threshold and shutdown to prevent it exceeding the voltage rating. | */ - MAV_GENERATOR_STATUS_FLAG_BATTERY_UNDERVOLT_FAULT=262144, /* Batteries are under voltage (generator will not start). | */ - MAV_GENERATOR_STATUS_FLAG_START_INHIBITED=524288, /* Generator start is inhibited by e.g. a safety switch. | */ - MAV_GENERATOR_STATUS_FLAG_MAINTENANCE_REQUIRED=1048576, /* Generator requires maintenance. | */ - MAV_GENERATOR_STATUS_FLAG_WARMING_UP=2097152, /* Generator is not ready to generate yet. | */ - MAV_GENERATOR_STATUS_FLAG_IDLE=4194304, /* Generator is idle. | */ - MAV_GENERATOR_STATUS_FLAG_ENUM_END=4194305, /* | */ -} MAV_GENERATOR_STATUS_FLAG; -#endif - -/** @brief Enumeration of VTOL states */ -#ifndef HAVE_ENUM_MAV_VTOL_STATE -#define HAVE_ENUM_MAV_VTOL_STATE -typedef enum MAV_VTOL_STATE -{ - MAV_VTOL_STATE_UNDEFINED=0, /* MAV is not configured as VTOL | */ - MAV_VTOL_STATE_TRANSITION_TO_FW=1, /* VTOL is in transition from multicopter to fixed-wing | */ - MAV_VTOL_STATE_TRANSITION_TO_MC=2, /* VTOL is in transition from fixed-wing to multicopter | */ - MAV_VTOL_STATE_MC=3, /* VTOL is in multicopter state | */ - MAV_VTOL_STATE_FW=4, /* VTOL is in fixed-wing state | */ - MAV_VTOL_STATE_ENUM_END=5, /* | */ -} MAV_VTOL_STATE; -#endif - -/** @brief Enumeration of landed detector states */ -#ifndef HAVE_ENUM_MAV_LANDED_STATE -#define HAVE_ENUM_MAV_LANDED_STATE -typedef enum MAV_LANDED_STATE -{ - MAV_LANDED_STATE_UNDEFINED=0, /* MAV landed state is unknown | */ - MAV_LANDED_STATE_ON_GROUND=1, /* MAV is landed (on ground) | */ - MAV_LANDED_STATE_IN_AIR=2, /* MAV is in air | */ - MAV_LANDED_STATE_TAKEOFF=3, /* MAV currently taking off | */ - MAV_LANDED_STATE_LANDING=4, /* MAV currently landing | */ - MAV_LANDED_STATE_ENUM_END=5, /* | */ -} MAV_LANDED_STATE; -#endif - -/** @brief Enumeration of the ADSB altimeter types */ -#ifndef HAVE_ENUM_ADSB_ALTITUDE_TYPE -#define HAVE_ENUM_ADSB_ALTITUDE_TYPE -typedef enum ADSB_ALTITUDE_TYPE -{ - ADSB_ALTITUDE_TYPE_PRESSURE_QNH=0, /* Altitude reported from a Baro source using QNH reference | */ - ADSB_ALTITUDE_TYPE_GEOMETRIC=1, /* Altitude reported from a GNSS source | */ - ADSB_ALTITUDE_TYPE_ENUM_END=2, /* | */ -} ADSB_ALTITUDE_TYPE; -#endif - -/** @brief ADSB classification for the type of vehicle emitting the transponder signal */ -#ifndef HAVE_ENUM_ADSB_EMITTER_TYPE -#define HAVE_ENUM_ADSB_EMITTER_TYPE -typedef enum ADSB_EMITTER_TYPE -{ - ADSB_EMITTER_TYPE_NO_INFO=0, /* | */ - ADSB_EMITTER_TYPE_LIGHT=1, /* | */ - ADSB_EMITTER_TYPE_SMALL=2, /* | */ - ADSB_EMITTER_TYPE_LARGE=3, /* | */ - ADSB_EMITTER_TYPE_HIGH_VORTEX_LARGE=4, /* | */ - ADSB_EMITTER_TYPE_HEAVY=5, /* | */ - ADSB_EMITTER_TYPE_HIGHLY_MANUV=6, /* | */ - ADSB_EMITTER_TYPE_ROTOCRAFT=7, /* | */ - ADSB_EMITTER_TYPE_UNASSIGNED=8, /* | */ - ADSB_EMITTER_TYPE_GLIDER=9, /* | */ - ADSB_EMITTER_TYPE_LIGHTER_AIR=10, /* | */ - ADSB_EMITTER_TYPE_PARACHUTE=11, /* | */ - ADSB_EMITTER_TYPE_ULTRA_LIGHT=12, /* | */ - ADSB_EMITTER_TYPE_UNASSIGNED2=13, /* | */ - ADSB_EMITTER_TYPE_UAV=14, /* | */ - ADSB_EMITTER_TYPE_SPACE=15, /* | */ - ADSB_EMITTER_TYPE_UNASSGINED3=16, /* | */ - ADSB_EMITTER_TYPE_EMERGENCY_SURFACE=17, /* | */ - ADSB_EMITTER_TYPE_SERVICE_SURFACE=18, /* | */ - ADSB_EMITTER_TYPE_POINT_OBSTACLE=19, /* | */ - ADSB_EMITTER_TYPE_ENUM_END=20, /* | */ -} ADSB_EMITTER_TYPE; -#endif - -/** @brief These flags indicate status such as data validity of each data source. Set = data valid */ -#ifndef HAVE_ENUM_ADSB_FLAGS -#define HAVE_ENUM_ADSB_FLAGS -typedef enum ADSB_FLAGS -{ - ADSB_FLAGS_VALID_COORDS=1, /* | */ - ADSB_FLAGS_VALID_ALTITUDE=2, /* | */ - ADSB_FLAGS_VALID_HEADING=4, /* | */ - ADSB_FLAGS_VALID_VELOCITY=8, /* | */ - ADSB_FLAGS_VALID_CALLSIGN=16, /* | */ - ADSB_FLAGS_VALID_SQUAWK=32, /* | */ - ADSB_FLAGS_SIMULATED=64, /* | */ - ADSB_FLAGS_VERTICAL_VELOCITY_VALID=128, /* | */ - ADSB_FLAGS_BARO_VALID=256, /* | */ - ADSB_FLAGS_SOURCE_UAT=32768, /* | */ - ADSB_FLAGS_ENUM_END=32769, /* | */ -} ADSB_FLAGS; -#endif - -/** @brief Bitmap of options for the MAV_CMD_DO_REPOSITION */ -#ifndef HAVE_ENUM_MAV_DO_REPOSITION_FLAGS -#define HAVE_ENUM_MAV_DO_REPOSITION_FLAGS -typedef enum MAV_DO_REPOSITION_FLAGS -{ - MAV_DO_REPOSITION_FLAGS_CHANGE_MODE=1, /* The aircraft should immediately transition into guided. This should not be set for follow me applications | */ - MAV_DO_REPOSITION_FLAGS_ENUM_END=2, /* | */ -} MAV_DO_REPOSITION_FLAGS; -#endif - -/** @brief Flags in ESTIMATOR_STATUS message */ -#ifndef HAVE_ENUM_ESTIMATOR_STATUS_FLAGS -#define HAVE_ENUM_ESTIMATOR_STATUS_FLAGS -typedef enum ESTIMATOR_STATUS_FLAGS -{ - ESTIMATOR_ATTITUDE=1, /* True if the attitude estimate is good | */ - ESTIMATOR_VELOCITY_HORIZ=2, /* True if the horizontal velocity estimate is good | */ - ESTIMATOR_VELOCITY_VERT=4, /* True if the vertical velocity estimate is good | */ - ESTIMATOR_POS_HORIZ_REL=8, /* True if the horizontal position (relative) estimate is good | */ - ESTIMATOR_POS_HORIZ_ABS=16, /* True if the horizontal position (absolute) estimate is good | */ - ESTIMATOR_POS_VERT_ABS=32, /* True if the vertical position (absolute) estimate is good | */ - ESTIMATOR_POS_VERT_AGL=64, /* True if the vertical position (above ground) estimate is good | */ - ESTIMATOR_CONST_POS_MODE=128, /* True if the EKF is in a constant position mode and is not using external measurements (eg GPS or optical flow) | */ - ESTIMATOR_PRED_POS_HORIZ_REL=256, /* True if the EKF has sufficient data to enter a mode that will provide a (relative) position estimate | */ - ESTIMATOR_PRED_POS_HORIZ_ABS=512, /* True if the EKF has sufficient data to enter a mode that will provide a (absolute) position estimate | */ - ESTIMATOR_GPS_GLITCH=1024, /* True if the EKF has detected a GPS glitch | */ - ESTIMATOR_ACCEL_ERROR=2048, /* True if the EKF has detected bad accelerometer data | */ - ESTIMATOR_STATUS_FLAGS_ENUM_END=2049, /* | */ -} ESTIMATOR_STATUS_FLAGS; -#endif - -/** @brief Sequence that motors are tested when using MAV_CMD_DO_MOTOR_TEST. */ -#ifndef HAVE_ENUM_MOTOR_TEST_ORDER -#define HAVE_ENUM_MOTOR_TEST_ORDER -typedef enum MOTOR_TEST_ORDER -{ - MOTOR_TEST_ORDER_DEFAULT=0, /* Default autopilot motor test method. | */ - MOTOR_TEST_ORDER_SEQUENCE=1, /* Motor numbers are specified as their index in a predefined vehicle-specific sequence. | */ - MOTOR_TEST_ORDER_BOARD=2, /* Motor numbers are specified as the output as labeled on the board. | */ - MOTOR_TEST_ORDER_ENUM_END=3, /* | */ -} MOTOR_TEST_ORDER; -#endif - -/** @brief Defines how throttle value is represented in MAV_CMD_DO_MOTOR_TEST. */ -#ifndef HAVE_ENUM_MOTOR_TEST_THROTTLE_TYPE -#define HAVE_ENUM_MOTOR_TEST_THROTTLE_TYPE -typedef enum MOTOR_TEST_THROTTLE_TYPE -{ - MOTOR_TEST_THROTTLE_PERCENT=0, /* Throttle as a percentage (0 ~ 100) | */ - MOTOR_TEST_THROTTLE_PWM=1, /* Throttle as an absolute PWM value (normally in range of 1000~2000). | */ - MOTOR_TEST_THROTTLE_PILOT=2, /* Throttle pass-through from pilot's transmitter. | */ - MOTOR_TEST_COMPASS_CAL=3, /* Per-motor compass calibration test. | */ - MOTOR_TEST_THROTTLE_TYPE_ENUM_END=4, /* | */ -} MOTOR_TEST_THROTTLE_TYPE; -#endif - -/** @brief */ -#ifndef HAVE_ENUM_GPS_INPUT_IGNORE_FLAGS -#define HAVE_ENUM_GPS_INPUT_IGNORE_FLAGS -typedef enum GPS_INPUT_IGNORE_FLAGS -{ - GPS_INPUT_IGNORE_FLAG_ALT=1, /* ignore altitude field | */ - GPS_INPUT_IGNORE_FLAG_HDOP=2, /* ignore hdop field | */ - GPS_INPUT_IGNORE_FLAG_VDOP=4, /* ignore vdop field | */ - GPS_INPUT_IGNORE_FLAG_VEL_HORIZ=8, /* ignore horizontal velocity field (vn and ve) | */ - GPS_INPUT_IGNORE_FLAG_VEL_VERT=16, /* ignore vertical velocity field (vd) | */ - GPS_INPUT_IGNORE_FLAG_SPEED_ACCURACY=32, /* ignore speed accuracy field | */ - GPS_INPUT_IGNORE_FLAG_HORIZONTAL_ACCURACY=64, /* ignore horizontal accuracy field | */ - GPS_INPUT_IGNORE_FLAG_VERTICAL_ACCURACY=128, /* ignore vertical accuracy field | */ - GPS_INPUT_IGNORE_FLAGS_ENUM_END=129, /* | */ -} GPS_INPUT_IGNORE_FLAGS; -#endif - -/** @brief Possible actions an aircraft can take to avoid a collision. */ -#ifndef HAVE_ENUM_MAV_COLLISION_ACTION -#define HAVE_ENUM_MAV_COLLISION_ACTION -typedef enum MAV_COLLISION_ACTION -{ - MAV_COLLISION_ACTION_NONE=0, /* Ignore any potential collisions | */ - MAV_COLLISION_ACTION_REPORT=1, /* Report potential collision | */ - MAV_COLLISION_ACTION_ASCEND_OR_DESCEND=2, /* Ascend or Descend to avoid threat | */ - MAV_COLLISION_ACTION_MOVE_HORIZONTALLY=3, /* Move horizontally to avoid threat | */ - MAV_COLLISION_ACTION_MOVE_PERPENDICULAR=4, /* Aircraft to move perpendicular to the collision's velocity vector | */ - MAV_COLLISION_ACTION_RTL=5, /* Aircraft to fly directly back to its launch point | */ - MAV_COLLISION_ACTION_HOVER=6, /* Aircraft to stop in place | */ - MAV_COLLISION_ACTION_ENUM_END=7, /* | */ -} MAV_COLLISION_ACTION; -#endif - -/** @brief Aircraft-rated danger from this threat. */ -#ifndef HAVE_ENUM_MAV_COLLISION_THREAT_LEVEL -#define HAVE_ENUM_MAV_COLLISION_THREAT_LEVEL -typedef enum MAV_COLLISION_THREAT_LEVEL -{ - MAV_COLLISION_THREAT_LEVEL_NONE=0, /* Not a threat | */ - MAV_COLLISION_THREAT_LEVEL_LOW=1, /* Craft is mildly concerned about this threat | */ - MAV_COLLISION_THREAT_LEVEL_HIGH=2, /* Craft is panicking, and may take actions to avoid threat | */ - MAV_COLLISION_THREAT_LEVEL_ENUM_END=3, /* | */ -} MAV_COLLISION_THREAT_LEVEL; -#endif - -/** @brief Source of information about this collision. */ -#ifndef HAVE_ENUM_MAV_COLLISION_SRC -#define HAVE_ENUM_MAV_COLLISION_SRC -typedef enum MAV_COLLISION_SRC -{ - MAV_COLLISION_SRC_ADSB=0, /* ID field references ADSB_VEHICLE packets | */ - MAV_COLLISION_SRC_MAVLINK_GPS_GLOBAL_INT=1, /* ID field references MAVLink SRC ID | */ - MAV_COLLISION_SRC_ENUM_END=2, /* | */ -} MAV_COLLISION_SRC; -#endif - -/** @brief Type of GPS fix */ -#ifndef HAVE_ENUM_GPS_FIX_TYPE -#define HAVE_ENUM_GPS_FIX_TYPE -typedef enum GPS_FIX_TYPE -{ - GPS_FIX_TYPE_NO_GPS=0, /* No GPS connected | */ - GPS_FIX_TYPE_NO_FIX=1, /* No position information, GPS is connected | */ - GPS_FIX_TYPE_2D_FIX=2, /* 2D position | */ - GPS_FIX_TYPE_3D_FIX=3, /* 3D position | */ - GPS_FIX_TYPE_DGPS=4, /* DGPS/SBAS aided 3D position | */ - GPS_FIX_TYPE_RTK_FLOAT=5, /* RTK float, 3D position | */ - GPS_FIX_TYPE_RTK_FIXED=6, /* RTK Fixed, 3D position | */ - GPS_FIX_TYPE_STATIC=7, /* Static fixed, typically used for base stations | */ - GPS_FIX_TYPE_PPP=8, /* PPP, 3D position. | */ - GPS_FIX_TYPE_ENUM_END=9, /* | */ -} GPS_FIX_TYPE; -#endif - -/** @brief RTK GPS baseline coordinate system, used for RTK corrections */ -#ifndef HAVE_ENUM_RTK_BASELINE_COORDINATE_SYSTEM -#define HAVE_ENUM_RTK_BASELINE_COORDINATE_SYSTEM -typedef enum RTK_BASELINE_COORDINATE_SYSTEM -{ - RTK_BASELINE_COORDINATE_SYSTEM_ECEF=0, /* Earth-centered, Earth-fixed | */ - RTK_BASELINE_COORDINATE_SYSTEM_NED=1, /* RTK basestation centered, north, east, down | */ - RTK_BASELINE_COORDINATE_SYSTEM_ENUM_END=2, /* | */ -} RTK_BASELINE_COORDINATE_SYSTEM; -#endif - -/** @brief Type of landing target */ -#ifndef HAVE_ENUM_LANDING_TARGET_TYPE -#define HAVE_ENUM_LANDING_TARGET_TYPE -typedef enum LANDING_TARGET_TYPE -{ - LANDING_TARGET_TYPE_LIGHT_BEACON=0, /* Landing target signaled by light beacon (ex: IR-LOCK) | */ - LANDING_TARGET_TYPE_RADIO_BEACON=1, /* Landing target signaled by radio beacon (ex: ILS, NDB) | */ - LANDING_TARGET_TYPE_VISION_FIDUCIAL=2, /* Landing target represented by a fiducial marker (ex: ARTag) | */ - LANDING_TARGET_TYPE_VISION_OTHER=3, /* Landing target represented by a pre-defined visual shape/feature (ex: X-marker, H-marker, square) | */ - LANDING_TARGET_TYPE_ENUM_END=4, /* | */ -} LANDING_TARGET_TYPE; -#endif - -/** @brief Direction of VTOL transition */ -#ifndef HAVE_ENUM_VTOL_TRANSITION_HEADING -#define HAVE_ENUM_VTOL_TRANSITION_HEADING -typedef enum VTOL_TRANSITION_HEADING -{ - VTOL_TRANSITION_HEADING_VEHICLE_DEFAULT=0, /* Respect the heading configuration of the vehicle. | */ - VTOL_TRANSITION_HEADING_NEXT_WAYPOINT=1, /* Use the heading pointing towards the next waypoint. | */ - VTOL_TRANSITION_HEADING_TAKEOFF=2, /* Use the heading on takeoff (while sitting on the ground). | */ - VTOL_TRANSITION_HEADING_SPECIFIED=3, /* Use the specified heading in parameter 4. | */ - VTOL_TRANSITION_HEADING_ANY=4, /* Use the current heading when reaching takeoff altitude (potentially facing the wind when weather-vaning is active). | */ - VTOL_TRANSITION_HEADING_ENUM_END=5, /* | */ -} VTOL_TRANSITION_HEADING; -#endif - -/** @brief Camera capability flags (Bitmap) */ -#ifndef HAVE_ENUM_CAMERA_CAP_FLAGS -#define HAVE_ENUM_CAMERA_CAP_FLAGS -typedef enum CAMERA_CAP_FLAGS -{ - CAMERA_CAP_FLAGS_CAPTURE_VIDEO=1, /* Camera is able to record video | */ - CAMERA_CAP_FLAGS_CAPTURE_IMAGE=2, /* Camera is able to capture images | */ - CAMERA_CAP_FLAGS_HAS_MODES=4, /* Camera has separate Video and Image/Photo modes (MAV_CMD_SET_CAMERA_MODE) | */ - CAMERA_CAP_FLAGS_CAN_CAPTURE_IMAGE_IN_VIDEO_MODE=8, /* Camera can capture images while in video mode | */ - CAMERA_CAP_FLAGS_CAN_CAPTURE_VIDEO_IN_IMAGE_MODE=16, /* Camera can capture videos while in Photo/Image mode | */ - CAMERA_CAP_FLAGS_HAS_IMAGE_SURVEY_MODE=32, /* Camera has image survey mode (MAV_CMD_SET_CAMERA_MODE) | */ - CAMERA_CAP_FLAGS_HAS_BASIC_ZOOM=64, /* Camera has basic zoom control (MAV_CMD_SET_CAMERA_ZOOM) | */ - CAMERA_CAP_FLAGS_HAS_BASIC_FOCUS=128, /* Camera has basic focus control (MAV_CMD_SET_CAMERA_FOCUS) | */ - CAMERA_CAP_FLAGS_HAS_VIDEO_STREAM=256, /* Camera has video streaming capabilities (request VIDEO_STREAM_INFORMATION with MAV_CMD_REQUEST_MESSAGE for video streaming info) | */ - CAMERA_CAP_FLAGS_HAS_TRACKING_POINT=512, /* Camera supports tracking of a point on the camera view. | */ - CAMERA_CAP_FLAGS_HAS_TRACKING_RECTANGLE=1024, /* Camera supports tracking of a selection rectangle on the camera view. | */ - CAMERA_CAP_FLAGS_HAS_TRACKING_GEO_STATUS=2048, /* Camera supports tracking geo status (CAMERA_TRACKING_GEO_STATUS). | */ - CAMERA_CAP_FLAGS_ENUM_END=2049, /* | */ -} CAMERA_CAP_FLAGS; -#endif - -/** @brief Stream status flags (Bitmap) */ -#ifndef HAVE_ENUM_VIDEO_STREAM_STATUS_FLAGS -#define HAVE_ENUM_VIDEO_STREAM_STATUS_FLAGS -typedef enum VIDEO_STREAM_STATUS_FLAGS -{ - VIDEO_STREAM_STATUS_FLAGS_RUNNING=1, /* Stream is active (running) | */ - VIDEO_STREAM_STATUS_FLAGS_THERMAL=2, /* Stream is thermal imaging | */ - VIDEO_STREAM_STATUS_FLAGS_ENUM_END=3, /* | */ -} VIDEO_STREAM_STATUS_FLAGS; -#endif - -/** @brief Video stream types */ -#ifndef HAVE_ENUM_VIDEO_STREAM_TYPE -#define HAVE_ENUM_VIDEO_STREAM_TYPE -typedef enum VIDEO_STREAM_TYPE -{ - VIDEO_STREAM_TYPE_RTSP=0, /* Stream is RTSP | */ - VIDEO_STREAM_TYPE_RTPUDP=1, /* Stream is RTP UDP (URI gives the port number) | */ - VIDEO_STREAM_TYPE_TCP_MPEG=2, /* Stream is MPEG on TCP | */ - VIDEO_STREAM_TYPE_MPEG_TS_H264=3, /* Stream is h.264 on MPEG TS (URI gives the port number) | */ - VIDEO_STREAM_TYPE_ENUM_END=4, /* | */ -} VIDEO_STREAM_TYPE; -#endif - -/** @brief Camera tracking status flags */ -#ifndef HAVE_ENUM_CAMERA_TRACKING_STATUS_FLAGS -#define HAVE_ENUM_CAMERA_TRACKING_STATUS_FLAGS -typedef enum CAMERA_TRACKING_STATUS_FLAGS -{ - CAMERA_TRACKING_STATUS_FLAGS_IDLE=0, /* Camera is not tracking | */ - CAMERA_TRACKING_STATUS_FLAGS_ACTIVE=1, /* Camera is tracking | */ - CAMERA_TRACKING_STATUS_FLAGS_ERROR=2, /* Camera tracking in error state | */ - CAMERA_TRACKING_STATUS_FLAGS_ENUM_END=3, /* | */ -} CAMERA_TRACKING_STATUS_FLAGS; -#endif - -/** @brief Camera tracking modes */ -#ifndef HAVE_ENUM_CAMERA_TRACKING_MODE -#define HAVE_ENUM_CAMERA_TRACKING_MODE -typedef enum CAMERA_TRACKING_MODE -{ - CAMERA_TRACKING_MODE_NONE=0, /* Not tracking | */ - CAMERA_TRACKING_MODE_POINT=1, /* Target is a point | */ - CAMERA_TRACKING_MODE_RECTANGLE=2, /* Target is a rectangle | */ - CAMERA_TRACKING_MODE_ENUM_END=3, /* | */ -} CAMERA_TRACKING_MODE; -#endif - -/** @brief Camera tracking target data (shows where tracked target is within image) */ -#ifndef HAVE_ENUM_CAMERA_TRACKING_TARGET_DATA -#define HAVE_ENUM_CAMERA_TRACKING_TARGET_DATA -typedef enum CAMERA_TRACKING_TARGET_DATA -{ - CAMERA_TRACKING_TARGET_DATA_NONE=0, /* No target data | */ - CAMERA_TRACKING_TARGET_DATA_EMBEDDED=1, /* Target data embedded in image data (proprietary) | */ - CAMERA_TRACKING_TARGET_DATA_RENDERED=2, /* Target data rendered in image | */ - CAMERA_TRACKING_TARGET_DATA_IN_STATUS=4, /* Target data within status message (Point or Rectangle) | */ - CAMERA_TRACKING_TARGET_DATA_ENUM_END=5, /* | */ -} CAMERA_TRACKING_TARGET_DATA; -#endif - -/** @brief Zoom types for MAV_CMD_SET_CAMERA_ZOOM */ -#ifndef HAVE_ENUM_CAMERA_ZOOM_TYPE -#define HAVE_ENUM_CAMERA_ZOOM_TYPE -typedef enum CAMERA_ZOOM_TYPE -{ - ZOOM_TYPE_STEP=0, /* Zoom one step increment (-1 for wide, 1 for tele) | */ - ZOOM_TYPE_CONTINUOUS=1, /* Continuous zoom up/down until stopped (-1 for wide, 1 for tele, 0 to stop zooming) | */ - ZOOM_TYPE_RANGE=2, /* Zoom value as proportion of full camera range (a percentage value between 0.0 and 100.0) | */ - ZOOM_TYPE_FOCAL_LENGTH=3, /* Zoom value/variable focal length in millimetres. Note that there is no message to get the valid zoom range of the camera, so this can type can only be used for cameras where the zoom range is known (implying that this cannot reliably be used in a GCS for an arbitrary camera) | */ - ZOOM_TYPE_HORIZONTAL_FOV=4, /* Zoom value as horizontal field of view in degrees. | */ - CAMERA_ZOOM_TYPE_ENUM_END=5, /* | */ -} CAMERA_ZOOM_TYPE; -#endif - -/** @brief Focus types for MAV_CMD_SET_CAMERA_FOCUS */ -#ifndef HAVE_ENUM_SET_FOCUS_TYPE -#define HAVE_ENUM_SET_FOCUS_TYPE -typedef enum SET_FOCUS_TYPE -{ - FOCUS_TYPE_STEP=0, /* Focus one step increment (-1 for focusing in, 1 for focusing out towards infinity). | */ - FOCUS_TYPE_CONTINUOUS=1, /* Continuous focus up/down until stopped (-1 for focusing in, 1 for focusing out towards infinity, 0 to stop focusing) | */ - FOCUS_TYPE_RANGE=2, /* Focus value as proportion of full camera focus range (a value between 0.0 and 100.0) | */ - FOCUS_TYPE_METERS=3, /* Focus value in metres. Note that there is no message to get the valid focus range of the camera, so this can type can only be used for cameras where the range is known (implying that this cannot reliably be used in a GCS for an arbitrary camera). | */ - FOCUS_TYPE_AUTO=4, /* Focus automatically. | */ - FOCUS_TYPE_AUTO_SINGLE=5, /* Single auto focus. Mainly used for still pictures. Usually abbreviated as AF-S. | */ - FOCUS_TYPE_AUTO_CONTINUOUS=6, /* Continuous auto focus. Mainly used for dynamic scenes. Abbreviated as AF-C. | */ - SET_FOCUS_TYPE_ENUM_END=7, /* | */ -} SET_FOCUS_TYPE; -#endif - -/** @brief Result from PARAM_EXT_SET message (or a PARAM_SET within a transaction). */ -#ifndef HAVE_ENUM_PARAM_ACK -#define HAVE_ENUM_PARAM_ACK -typedef enum PARAM_ACK -{ - PARAM_ACK_ACCEPTED=0, /* Parameter value ACCEPTED and SET | */ - PARAM_ACK_VALUE_UNSUPPORTED=1, /* Parameter value UNKNOWN/UNSUPPORTED | */ - PARAM_ACK_FAILED=2, /* Parameter failed to set | */ - PARAM_ACK_IN_PROGRESS=3, /* Parameter value received but not yet set/accepted. A subsequent PARAM_ACK_TRANSACTION or PARAM_EXT_ACK with the final result will follow once operation is completed. This is returned immediately for parameters that take longer to set, indicating that the the parameter was received and does not need to be resent. | */ - PARAM_ACK_ENUM_END=4, /* | */ -} PARAM_ACK; -#endif - -/** @brief Camera Modes. */ -#ifndef HAVE_ENUM_CAMERA_MODE -#define HAVE_ENUM_CAMERA_MODE -typedef enum CAMERA_MODE -{ - CAMERA_MODE_IMAGE=0, /* Camera is in image/photo capture mode. | */ - CAMERA_MODE_VIDEO=1, /* Camera is in video capture mode. | */ - CAMERA_MODE_IMAGE_SURVEY=2, /* Camera is in image survey capture mode. It allows for camera controller to do specific settings for surveys. | */ - CAMERA_MODE_ENUM_END=3, /* | */ -} CAMERA_MODE; -#endif - -/** @brief */ -#ifndef HAVE_ENUM_MAV_ARM_AUTH_DENIED_REASON -#define HAVE_ENUM_MAV_ARM_AUTH_DENIED_REASON -typedef enum MAV_ARM_AUTH_DENIED_REASON -{ - MAV_ARM_AUTH_DENIED_REASON_GENERIC=0, /* Not a specific reason | */ - MAV_ARM_AUTH_DENIED_REASON_NONE=1, /* Authorizer will send the error as string to GCS | */ - MAV_ARM_AUTH_DENIED_REASON_INVALID_WAYPOINT=2, /* At least one waypoint have a invalid value | */ - MAV_ARM_AUTH_DENIED_REASON_TIMEOUT=3, /* Timeout in the authorizer process(in case it depends on network) | */ - MAV_ARM_AUTH_DENIED_REASON_AIRSPACE_IN_USE=4, /* Airspace of the mission in use by another vehicle, second result parameter can have the waypoint id that caused it to be denied. | */ - MAV_ARM_AUTH_DENIED_REASON_BAD_WEATHER=5, /* Weather is not good to fly | */ - MAV_ARM_AUTH_DENIED_REASON_ENUM_END=6, /* | */ -} MAV_ARM_AUTH_DENIED_REASON; -#endif - -/** @brief RC type */ -#ifndef HAVE_ENUM_RC_TYPE -#define HAVE_ENUM_RC_TYPE -typedef enum RC_TYPE -{ - RC_TYPE_SPEKTRUM_DSM2=0, /* Spektrum DSM2 | */ - RC_TYPE_SPEKTRUM_DSMX=1, /* Spektrum DSMX | */ - RC_TYPE_ENUM_END=2, /* | */ -} RC_TYPE; -#endif - -/** @brief Bitmap to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 9 is set the floats afx afy afz should be interpreted as force instead of acceleration. */ -#ifndef HAVE_ENUM_POSITION_TARGET_TYPEMASK -#define HAVE_ENUM_POSITION_TARGET_TYPEMASK -typedef enum POSITION_TARGET_TYPEMASK -{ - POSITION_TARGET_TYPEMASK_X_IGNORE=1, /* Ignore position x | */ - POSITION_TARGET_TYPEMASK_Y_IGNORE=2, /* Ignore position y | */ - POSITION_TARGET_TYPEMASK_Z_IGNORE=4, /* Ignore position z | */ - POSITION_TARGET_TYPEMASK_VX_IGNORE=8, /* Ignore velocity x | */ - POSITION_TARGET_TYPEMASK_VY_IGNORE=16, /* Ignore velocity y | */ - POSITION_TARGET_TYPEMASK_VZ_IGNORE=32, /* Ignore velocity z | */ - POSITION_TARGET_TYPEMASK_AX_IGNORE=64, /* Ignore acceleration x | */ - POSITION_TARGET_TYPEMASK_AY_IGNORE=128, /* Ignore acceleration y | */ - POSITION_TARGET_TYPEMASK_AZ_IGNORE=256, /* Ignore acceleration z | */ - POSITION_TARGET_TYPEMASK_FORCE_SET=512, /* Use force instead of acceleration | */ - POSITION_TARGET_TYPEMASK_YAW_IGNORE=1024, /* Ignore yaw | */ - POSITION_TARGET_TYPEMASK_YAW_RATE_IGNORE=2048, /* Ignore yaw rate | */ - POSITION_TARGET_TYPEMASK_ENUM_END=2049, /* | */ -} POSITION_TARGET_TYPEMASK; -#endif - -/** @brief Bitmap to indicate which dimensions should be ignored by the vehicle: a value of 0b00000000 indicates that none of the setpoint dimensions should be ignored. */ -#ifndef HAVE_ENUM_ATTITUDE_TARGET_TYPEMASK -#define HAVE_ENUM_ATTITUDE_TARGET_TYPEMASK -typedef enum ATTITUDE_TARGET_TYPEMASK -{ - ATTITUDE_TARGET_TYPEMASK_BODY_ROLL_RATE_IGNORE=1, /* Ignore body roll rate | */ - ATTITUDE_TARGET_TYPEMASK_BODY_PITCH_RATE_IGNORE=2, /* Ignore body pitch rate | */ - ATTITUDE_TARGET_TYPEMASK_BODY_YAW_RATE_IGNORE=4, /* Ignore body yaw rate | */ - ATTITUDE_TARGET_TYPEMASK_THRUST_BODY_SET=32, /* Use 3D body thrust setpoint instead of throttle | */ - ATTITUDE_TARGET_TYPEMASK_THROTTLE_IGNORE=64, /* Ignore throttle | */ - ATTITUDE_TARGET_TYPEMASK_ATTITUDE_IGNORE=128, /* Ignore attitude | */ - ATTITUDE_TARGET_TYPEMASK_ENUM_END=129, /* | */ -} ATTITUDE_TARGET_TYPEMASK; -#endif - -/** @brief Airborne status of UAS. */ -#ifndef HAVE_ENUM_UTM_FLIGHT_STATE -#define HAVE_ENUM_UTM_FLIGHT_STATE -typedef enum UTM_FLIGHT_STATE -{ - UTM_FLIGHT_STATE_UNKNOWN=1, /* The flight state can't be determined. | */ - UTM_FLIGHT_STATE_GROUND=2, /* UAS on ground. | */ - UTM_FLIGHT_STATE_AIRBORNE=3, /* UAS airborne. | */ - UTM_FLIGHT_STATE_EMERGENCY=16, /* UAS is in an emergency flight state. | */ - UTM_FLIGHT_STATE_NOCTRL=32, /* UAS has no active controls. | */ - UTM_FLIGHT_STATE_ENUM_END=33, /* | */ -} UTM_FLIGHT_STATE; -#endif - -/** @brief Flags for the global position report. */ -#ifndef HAVE_ENUM_UTM_DATA_AVAIL_FLAGS -#define HAVE_ENUM_UTM_DATA_AVAIL_FLAGS -typedef enum UTM_DATA_AVAIL_FLAGS -{ - UTM_DATA_AVAIL_FLAGS_TIME_VALID=1, /* The field time contains valid data. | */ - UTM_DATA_AVAIL_FLAGS_UAS_ID_AVAILABLE=2, /* The field uas_id contains valid data. | */ - UTM_DATA_AVAIL_FLAGS_POSITION_AVAILABLE=4, /* The fields lat, lon and h_acc contain valid data. | */ - UTM_DATA_AVAIL_FLAGS_ALTITUDE_AVAILABLE=8, /* The fields alt and v_acc contain valid data. | */ - UTM_DATA_AVAIL_FLAGS_RELATIVE_ALTITUDE_AVAILABLE=16, /* The field relative_alt contains valid data. | */ - UTM_DATA_AVAIL_FLAGS_HORIZONTAL_VELO_AVAILABLE=32, /* The fields vx and vy contain valid data. | */ - UTM_DATA_AVAIL_FLAGS_VERTICAL_VELO_AVAILABLE=64, /* The field vz contains valid data. | */ - UTM_DATA_AVAIL_FLAGS_NEXT_WAYPOINT_AVAILABLE=128, /* The fields next_lat, next_lon and next_alt contain valid data. | */ - UTM_DATA_AVAIL_FLAGS_ENUM_END=129, /* | */ -} UTM_DATA_AVAIL_FLAGS; -#endif - -/** @brief These flags encode the cellular network status */ -#ifndef HAVE_ENUM_CELLULAR_STATUS_FLAG -#define HAVE_ENUM_CELLULAR_STATUS_FLAG -typedef enum CELLULAR_STATUS_FLAG -{ - CELLULAR_STATUS_FLAG_UNKNOWN=0, /* State unknown or not reportable. | */ - CELLULAR_STATUS_FLAG_FAILED=1, /* Modem is unusable | */ - CELLULAR_STATUS_FLAG_INITIALIZING=2, /* Modem is being initialized | */ - CELLULAR_STATUS_FLAG_LOCKED=3, /* Modem is locked | */ - CELLULAR_STATUS_FLAG_DISABLED=4, /* Modem is not enabled and is powered down | */ - CELLULAR_STATUS_FLAG_DISABLING=5, /* Modem is currently transitioning to the CELLULAR_STATUS_FLAG_DISABLED state | */ - CELLULAR_STATUS_FLAG_ENABLING=6, /* Modem is currently transitioning to the CELLULAR_STATUS_FLAG_ENABLED state | */ - CELLULAR_STATUS_FLAG_ENABLED=7, /* Modem is enabled and powered on but not registered with a network provider and not available for data connections | */ - CELLULAR_STATUS_FLAG_SEARCHING=8, /* Modem is searching for a network provider to register | */ - CELLULAR_STATUS_FLAG_REGISTERED=9, /* Modem is registered with a network provider, and data connections and messaging may be available for use | */ - CELLULAR_STATUS_FLAG_DISCONNECTING=10, /* Modem is disconnecting and deactivating the last active packet data bearer. This state will not be entered if more than one packet data bearer is active and one of the active bearers is deactivated | */ - CELLULAR_STATUS_FLAG_CONNECTING=11, /* Modem is activating and connecting the first packet data bearer. Subsequent bearer activations when another bearer is already active do not cause this state to be entered | */ - CELLULAR_STATUS_FLAG_CONNECTED=12, /* One or more packet data bearers is active and connected | */ - CELLULAR_STATUS_FLAG_ENUM_END=13, /* | */ -} CELLULAR_STATUS_FLAG; -#endif - -/** @brief These flags are used to diagnose the failure state of CELLULAR_STATUS */ -#ifndef HAVE_ENUM_CELLULAR_NETWORK_FAILED_REASON -#define HAVE_ENUM_CELLULAR_NETWORK_FAILED_REASON -typedef enum CELLULAR_NETWORK_FAILED_REASON -{ - CELLULAR_NETWORK_FAILED_REASON_NONE=0, /* No error | */ - CELLULAR_NETWORK_FAILED_REASON_UNKNOWN=1, /* Error state is unknown | */ - CELLULAR_NETWORK_FAILED_REASON_SIM_MISSING=2, /* SIM is required for the modem but missing | */ - CELLULAR_NETWORK_FAILED_REASON_SIM_ERROR=3, /* SIM is available, but not usable for connection | */ - CELLULAR_NETWORK_FAILED_REASON_ENUM_END=4, /* | */ -} CELLULAR_NETWORK_FAILED_REASON; -#endif - -/** @brief Cellular network radio type */ -#ifndef HAVE_ENUM_CELLULAR_NETWORK_RADIO_TYPE -#define HAVE_ENUM_CELLULAR_NETWORK_RADIO_TYPE -typedef enum CELLULAR_NETWORK_RADIO_TYPE -{ - CELLULAR_NETWORK_RADIO_TYPE_NONE=0, /* | */ - CELLULAR_NETWORK_RADIO_TYPE_GSM=1, /* | */ - CELLULAR_NETWORK_RADIO_TYPE_CDMA=2, /* | */ - CELLULAR_NETWORK_RADIO_TYPE_WCDMA=3, /* | */ - CELLULAR_NETWORK_RADIO_TYPE_LTE=4, /* | */ - CELLULAR_NETWORK_RADIO_TYPE_ENUM_END=5, /* | */ -} CELLULAR_NETWORK_RADIO_TYPE; -#endif - -/** @brief Precision land modes (used in MAV_CMD_NAV_LAND). */ -#ifndef HAVE_ENUM_PRECISION_LAND_MODE -#define HAVE_ENUM_PRECISION_LAND_MODE -typedef enum PRECISION_LAND_MODE -{ - PRECISION_LAND_MODE_DISABLED=0, /* Normal (non-precision) landing. | */ - PRECISION_LAND_MODE_OPPORTUNISTIC=1, /* Use precision landing if beacon detected when land command accepted, otherwise land normally. | */ - PRECISION_LAND_MODE_REQUIRED=2, /* Use precision landing, searching for beacon if not found when land command accepted (land normally if beacon cannot be found). | */ - PRECISION_LAND_MODE_ENUM_END=3, /* | */ -} PRECISION_LAND_MODE; -#endif - -/** @brief Parachute actions. Trigger release and enable/disable auto-release. */ -#ifndef HAVE_ENUM_PARACHUTE_ACTION -#define HAVE_ENUM_PARACHUTE_ACTION -typedef enum PARACHUTE_ACTION -{ - PARACHUTE_DISABLE=0, /* Disable auto-release of parachute (i.e. release triggered by crash detectors). | */ - PARACHUTE_ENABLE=1, /* Enable auto-release of parachute. | */ - PARACHUTE_RELEASE=2, /* Release parachute and kill motors. | */ - PARACHUTE_ACTION_ENUM_END=3, /* | */ -} PARACHUTE_ACTION; -#endif - -/** @brief */ -#ifndef HAVE_ENUM_MAV_TUNNEL_PAYLOAD_TYPE -#define HAVE_ENUM_MAV_TUNNEL_PAYLOAD_TYPE -typedef enum MAV_TUNNEL_PAYLOAD_TYPE -{ - MAV_TUNNEL_PAYLOAD_TYPE_UNKNOWN=0, /* Encoding of payload unknown. | */ - MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED0=200, /* Registered for STorM32 gimbal controller. | */ - MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED1=201, /* Registered for STorM32 gimbal controller. | */ - MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED2=202, /* Registered for STorM32 gimbal controller. | */ - MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED3=203, /* Registered for STorM32 gimbal controller. | */ - MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED4=204, /* Registered for STorM32 gimbal controller. | */ - MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED5=205, /* Registered for STorM32 gimbal controller. | */ - MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED6=206, /* Registered for STorM32 gimbal controller. | */ - MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED7=207, /* Registered for STorM32 gimbal controller. | */ - MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED8=208, /* Registered for STorM32 gimbal controller. | */ - MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED9=209, /* Registered for STorM32 gimbal controller. | */ - MAV_TUNNEL_PAYLOAD_TYPE_ENUM_END=210, /* | */ -} MAV_TUNNEL_PAYLOAD_TYPE; -#endif - -/** @brief */ -#ifndef HAVE_ENUM_MAV_ODID_ID_TYPE -#define HAVE_ENUM_MAV_ODID_ID_TYPE -typedef enum MAV_ODID_ID_TYPE -{ - MAV_ODID_ID_TYPE_NONE=0, /* No type defined. | */ - MAV_ODID_ID_TYPE_SERIAL_NUMBER=1, /* Manufacturer Serial Number (ANSI/CTA-2063 format). | */ - MAV_ODID_ID_TYPE_CAA_REGISTRATION_ID=2, /* CAA (Civil Aviation Authority) registered ID. Format: [ICAO Country Code].[CAA Assigned ID]. | */ - MAV_ODID_ID_TYPE_UTM_ASSIGNED_UUID=3, /* UTM (Unmanned Traffic Management) assigned UUID (RFC4122). | */ - MAV_ODID_ID_TYPE_SPECIFIC_SESSION_ID=4, /* A 20 byte ID for a specific flight/session. The exact ID type is indicated by the first byte of uas_id and these type values are managed by ICAO. | */ - MAV_ODID_ID_TYPE_ENUM_END=5, /* | */ -} MAV_ODID_ID_TYPE; -#endif - -/** @brief */ -#ifndef HAVE_ENUM_MAV_ODID_UA_TYPE -#define HAVE_ENUM_MAV_ODID_UA_TYPE -typedef enum MAV_ODID_UA_TYPE -{ - MAV_ODID_UA_TYPE_NONE=0, /* No UA (Unmanned Aircraft) type defined. | */ - MAV_ODID_UA_TYPE_AEROPLANE=1, /* Aeroplane/Airplane. Fixed wing. | */ - MAV_ODID_UA_TYPE_HELICOPTER_OR_MULTIROTOR=2, /* Helicopter or multirotor. | */ - MAV_ODID_UA_TYPE_GYROPLANE=3, /* Gyroplane. | */ - MAV_ODID_UA_TYPE_HYBRID_LIFT=4, /* VTOL (Vertical Take-Off and Landing). Fixed wing aircraft that can take off vertically. | */ - MAV_ODID_UA_TYPE_ORNITHOPTER=5, /* Ornithopter. | */ - MAV_ODID_UA_TYPE_GLIDER=6, /* Glider. | */ - MAV_ODID_UA_TYPE_KITE=7, /* Kite. | */ - MAV_ODID_UA_TYPE_FREE_BALLOON=8, /* Free Balloon. | */ - MAV_ODID_UA_TYPE_CAPTIVE_BALLOON=9, /* Captive Balloon. | */ - MAV_ODID_UA_TYPE_AIRSHIP=10, /* Airship. E.g. a blimp. | */ - MAV_ODID_UA_TYPE_FREE_FALL_PARACHUTE=11, /* Free Fall/Parachute (unpowered). | */ - MAV_ODID_UA_TYPE_ROCKET=12, /* Rocket. | */ - MAV_ODID_UA_TYPE_TETHERED_POWERED_AIRCRAFT=13, /* Tethered powered aircraft. | */ - MAV_ODID_UA_TYPE_GROUND_OBSTACLE=14, /* Ground Obstacle. | */ - MAV_ODID_UA_TYPE_OTHER=15, /* Other type of aircraft not listed earlier. | */ - MAV_ODID_UA_TYPE_ENUM_END=16, /* | */ -} MAV_ODID_UA_TYPE; -#endif - -/** @brief */ -#ifndef HAVE_ENUM_MAV_ODID_STATUS -#define HAVE_ENUM_MAV_ODID_STATUS -typedef enum MAV_ODID_STATUS -{ - MAV_ODID_STATUS_UNDECLARED=0, /* The status of the (UA) Unmanned Aircraft is undefined. | */ - MAV_ODID_STATUS_GROUND=1, /* The UA is on the ground. | */ - MAV_ODID_STATUS_AIRBORNE=2, /* The UA is in the air. | */ - MAV_ODID_STATUS_EMERGENCY=3, /* The UA is having an emergency. | */ - MAV_ODID_STATUS_REMOTE_ID_SYSTEM_FAILURE=4, /* The remote ID system is failing or unreliable in some way. | */ - MAV_ODID_STATUS_ENUM_END=5, /* | */ -} MAV_ODID_STATUS; -#endif - -/** @brief */ -#ifndef HAVE_ENUM_MAV_ODID_HEIGHT_REF -#define HAVE_ENUM_MAV_ODID_HEIGHT_REF -typedef enum MAV_ODID_HEIGHT_REF -{ - MAV_ODID_HEIGHT_REF_OVER_TAKEOFF=0, /* The height field is relative to the take-off location. | */ - MAV_ODID_HEIGHT_REF_OVER_GROUND=1, /* The height field is relative to ground. | */ - MAV_ODID_HEIGHT_REF_ENUM_END=2, /* | */ -} MAV_ODID_HEIGHT_REF; -#endif - -/** @brief */ -#ifndef HAVE_ENUM_MAV_ODID_HOR_ACC -#define HAVE_ENUM_MAV_ODID_HOR_ACC -typedef enum MAV_ODID_HOR_ACC -{ - MAV_ODID_HOR_ACC_UNKNOWN=0, /* The horizontal accuracy is unknown. | */ - MAV_ODID_HOR_ACC_10NM=1, /* The horizontal accuracy is smaller than 10 Nautical Miles. 18.52 km. | */ - MAV_ODID_HOR_ACC_4NM=2, /* The horizontal accuracy is smaller than 4 Nautical Miles. 7.408 km. | */ - MAV_ODID_HOR_ACC_2NM=3, /* The horizontal accuracy is smaller than 2 Nautical Miles. 3.704 km. | */ - MAV_ODID_HOR_ACC_1NM=4, /* The horizontal accuracy is smaller than 1 Nautical Miles. 1.852 km. | */ - MAV_ODID_HOR_ACC_0_5NM=5, /* The horizontal accuracy is smaller than 0.5 Nautical Miles. 926 m. | */ - MAV_ODID_HOR_ACC_0_3NM=6, /* The horizontal accuracy is smaller than 0.3 Nautical Miles. 555.6 m. | */ - MAV_ODID_HOR_ACC_0_1NM=7, /* The horizontal accuracy is smaller than 0.1 Nautical Miles. 185.2 m. | */ - MAV_ODID_HOR_ACC_0_05NM=8, /* The horizontal accuracy is smaller than 0.05 Nautical Miles. 92.6 m. | */ - MAV_ODID_HOR_ACC_30_METER=9, /* The horizontal accuracy is smaller than 30 meter. | */ - MAV_ODID_HOR_ACC_10_METER=10, /* The horizontal accuracy is smaller than 10 meter. | */ - MAV_ODID_HOR_ACC_3_METER=11, /* The horizontal accuracy is smaller than 3 meter. | */ - MAV_ODID_HOR_ACC_1_METER=12, /* The horizontal accuracy is smaller than 1 meter. | */ - MAV_ODID_HOR_ACC_ENUM_END=13, /* | */ -} MAV_ODID_HOR_ACC; -#endif - -/** @brief */ -#ifndef HAVE_ENUM_MAV_ODID_VER_ACC -#define HAVE_ENUM_MAV_ODID_VER_ACC -typedef enum MAV_ODID_VER_ACC -{ - MAV_ODID_VER_ACC_UNKNOWN=0, /* The vertical accuracy is unknown. | */ - MAV_ODID_VER_ACC_150_METER=1, /* The vertical accuracy is smaller than 150 meter. | */ - MAV_ODID_VER_ACC_45_METER=2, /* The vertical accuracy is smaller than 45 meter. | */ - MAV_ODID_VER_ACC_25_METER=3, /* The vertical accuracy is smaller than 25 meter. | */ - MAV_ODID_VER_ACC_10_METER=4, /* The vertical accuracy is smaller than 10 meter. | */ - MAV_ODID_VER_ACC_3_METER=5, /* The vertical accuracy is smaller than 3 meter. | */ - MAV_ODID_VER_ACC_1_METER=6, /* The vertical accuracy is smaller than 1 meter. | */ - MAV_ODID_VER_ACC_ENUM_END=7, /* | */ -} MAV_ODID_VER_ACC; -#endif - -/** @brief */ -#ifndef HAVE_ENUM_MAV_ODID_SPEED_ACC -#define HAVE_ENUM_MAV_ODID_SPEED_ACC -typedef enum MAV_ODID_SPEED_ACC -{ - MAV_ODID_SPEED_ACC_UNKNOWN=0, /* The speed accuracy is unknown. | */ - MAV_ODID_SPEED_ACC_10_METERS_PER_SECOND=1, /* The speed accuracy is smaller than 10 meters per second. | */ - MAV_ODID_SPEED_ACC_3_METERS_PER_SECOND=2, /* The speed accuracy is smaller than 3 meters per second. | */ - MAV_ODID_SPEED_ACC_1_METERS_PER_SECOND=3, /* The speed accuracy is smaller than 1 meters per second. | */ - MAV_ODID_SPEED_ACC_0_3_METERS_PER_SECOND=4, /* The speed accuracy is smaller than 0.3 meters per second. | */ - MAV_ODID_SPEED_ACC_ENUM_END=5, /* | */ -} MAV_ODID_SPEED_ACC; -#endif - -/** @brief */ -#ifndef HAVE_ENUM_MAV_ODID_TIME_ACC -#define HAVE_ENUM_MAV_ODID_TIME_ACC -typedef enum MAV_ODID_TIME_ACC -{ - MAV_ODID_TIME_ACC_UNKNOWN=0, /* The timestamp accuracy is unknown. | */ - MAV_ODID_TIME_ACC_0_1_SECOND=1, /* The timestamp accuracy is smaller than or equal to 0.1 second. | */ - MAV_ODID_TIME_ACC_0_2_SECOND=2, /* The timestamp accuracy is smaller than or equal to 0.2 second. | */ - MAV_ODID_TIME_ACC_0_3_SECOND=3, /* The timestamp accuracy is smaller than or equal to 0.3 second. | */ - MAV_ODID_TIME_ACC_0_4_SECOND=4, /* The timestamp accuracy is smaller than or equal to 0.4 second. | */ - MAV_ODID_TIME_ACC_0_5_SECOND=5, /* The timestamp accuracy is smaller than or equal to 0.5 second. | */ - MAV_ODID_TIME_ACC_0_6_SECOND=6, /* The timestamp accuracy is smaller than or equal to 0.6 second. | */ - MAV_ODID_TIME_ACC_0_7_SECOND=7, /* The timestamp accuracy is smaller than or equal to 0.7 second. | */ - MAV_ODID_TIME_ACC_0_8_SECOND=8, /* The timestamp accuracy is smaller than or equal to 0.8 second. | */ - MAV_ODID_TIME_ACC_0_9_SECOND=9, /* The timestamp accuracy is smaller than or equal to 0.9 second. | */ - MAV_ODID_TIME_ACC_1_0_SECOND=10, /* The timestamp accuracy is smaller than or equal to 1.0 second. | */ - MAV_ODID_TIME_ACC_1_1_SECOND=11, /* The timestamp accuracy is smaller than or equal to 1.1 second. | */ - MAV_ODID_TIME_ACC_1_2_SECOND=12, /* The timestamp accuracy is smaller than or equal to 1.2 second. | */ - MAV_ODID_TIME_ACC_1_3_SECOND=13, /* The timestamp accuracy is smaller than or equal to 1.3 second. | */ - MAV_ODID_TIME_ACC_1_4_SECOND=14, /* The timestamp accuracy is smaller than or equal to 1.4 second. | */ - MAV_ODID_TIME_ACC_1_5_SECOND=15, /* The timestamp accuracy is smaller than or equal to 1.5 second. | */ - MAV_ODID_TIME_ACC_ENUM_END=16, /* | */ -} MAV_ODID_TIME_ACC; -#endif - -/** @brief */ -#ifndef HAVE_ENUM_MAV_ODID_AUTH_TYPE -#define HAVE_ENUM_MAV_ODID_AUTH_TYPE -typedef enum MAV_ODID_AUTH_TYPE -{ - MAV_ODID_AUTH_TYPE_NONE=0, /* No authentication type is specified. | */ - MAV_ODID_AUTH_TYPE_UAS_ID_SIGNATURE=1, /* Signature for the UAS (Unmanned Aircraft System) ID. | */ - MAV_ODID_AUTH_TYPE_OPERATOR_ID_SIGNATURE=2, /* Signature for the Operator ID. | */ - MAV_ODID_AUTH_TYPE_MESSAGE_SET_SIGNATURE=3, /* Signature for the entire message set. | */ - MAV_ODID_AUTH_TYPE_NETWORK_REMOTE_ID=4, /* Authentication is provided by Network Remote ID. | */ - MAV_ODID_AUTH_TYPE_SPECIFIC_AUTHENTICATION=5, /* The exact authentication type is indicated by the first byte of authentication_data and these type values are managed by ICAO. | */ - MAV_ODID_AUTH_TYPE_ENUM_END=6, /* | */ -} MAV_ODID_AUTH_TYPE; -#endif - -/** @brief */ -#ifndef HAVE_ENUM_MAV_ODID_DESC_TYPE -#define HAVE_ENUM_MAV_ODID_DESC_TYPE -typedef enum MAV_ODID_DESC_TYPE -{ - MAV_ODID_DESC_TYPE_TEXT=0, /* Optional free-form text description of the purpose of the flight. | */ - MAV_ODID_DESC_TYPE_EMERGENCY=1, /* Optional additional clarification when status == MAV_ODID_STATUS_EMERGENCY. | */ - MAV_ODID_DESC_TYPE_EXTENDED_STATUS=2, /* Optional additional clarification when status != MAV_ODID_STATUS_EMERGENCY. | */ - MAV_ODID_DESC_TYPE_ENUM_END=3, /* | */ -} MAV_ODID_DESC_TYPE; -#endif - -/** @brief */ -#ifndef HAVE_ENUM_MAV_ODID_OPERATOR_LOCATION_TYPE -#define HAVE_ENUM_MAV_ODID_OPERATOR_LOCATION_TYPE -typedef enum MAV_ODID_OPERATOR_LOCATION_TYPE -{ - MAV_ODID_OPERATOR_LOCATION_TYPE_TAKEOFF=0, /* The location/altitude of the operator is the same as the take-off location. | */ - MAV_ODID_OPERATOR_LOCATION_TYPE_LIVE_GNSS=1, /* The location/altitude of the operator is dynamic. E.g. based on live GNSS data. | */ - MAV_ODID_OPERATOR_LOCATION_TYPE_FIXED=2, /* The location/altitude of the operator are fixed values. | */ - MAV_ODID_OPERATOR_LOCATION_TYPE_ENUM_END=3, /* | */ -} MAV_ODID_OPERATOR_LOCATION_TYPE; -#endif - -/** @brief */ -#ifndef HAVE_ENUM_MAV_ODID_CLASSIFICATION_TYPE -#define HAVE_ENUM_MAV_ODID_CLASSIFICATION_TYPE -typedef enum MAV_ODID_CLASSIFICATION_TYPE -{ - MAV_ODID_CLASSIFICATION_TYPE_UNDECLARED=0, /* The classification type for the UA is undeclared. | */ - MAV_ODID_CLASSIFICATION_TYPE_EU=1, /* The classification type for the UA follows EU (European Union) specifications. | */ - MAV_ODID_CLASSIFICATION_TYPE_ENUM_END=2, /* | */ -} MAV_ODID_CLASSIFICATION_TYPE; -#endif - -/** @brief */ -#ifndef HAVE_ENUM_MAV_ODID_CATEGORY_EU -#define HAVE_ENUM_MAV_ODID_CATEGORY_EU -typedef enum MAV_ODID_CATEGORY_EU -{ - MAV_ODID_CATEGORY_EU_UNDECLARED=0, /* The category for the UA, according to the EU specification, is undeclared. | */ - MAV_ODID_CATEGORY_EU_OPEN=1, /* The category for the UA, according to the EU specification, is the Open category. | */ - MAV_ODID_CATEGORY_EU_SPECIFIC=2, /* The category for the UA, according to the EU specification, is the Specific category. | */ - MAV_ODID_CATEGORY_EU_CERTIFIED=3, /* The category for the UA, according to the EU specification, is the Certified category. | */ - MAV_ODID_CATEGORY_EU_ENUM_END=4, /* | */ -} MAV_ODID_CATEGORY_EU; -#endif - -/** @brief */ -#ifndef HAVE_ENUM_MAV_ODID_CLASS_EU -#define HAVE_ENUM_MAV_ODID_CLASS_EU -typedef enum MAV_ODID_CLASS_EU -{ - MAV_ODID_CLASS_EU_UNDECLARED=0, /* The class for the UA, according to the EU specification, is undeclared. | */ - MAV_ODID_CLASS_EU_CLASS_0=1, /* The class for the UA, according to the EU specification, is Class 0. | */ - MAV_ODID_CLASS_EU_CLASS_1=2, /* The class for the UA, according to the EU specification, is Class 1. | */ - MAV_ODID_CLASS_EU_CLASS_2=3, /* The class for the UA, according to the EU specification, is Class 2. | */ - MAV_ODID_CLASS_EU_CLASS_3=4, /* The class for the UA, according to the EU specification, is Class 3. | */ - MAV_ODID_CLASS_EU_CLASS_4=5, /* The class for the UA, according to the EU specification, is Class 4. | */ - MAV_ODID_CLASS_EU_CLASS_5=6, /* The class for the UA, according to the EU specification, is Class 5. | */ - MAV_ODID_CLASS_EU_CLASS_6=7, /* The class for the UA, according to the EU specification, is Class 6. | */ - MAV_ODID_CLASS_EU_ENUM_END=8, /* | */ -} MAV_ODID_CLASS_EU; -#endif - -/** @brief */ -#ifndef HAVE_ENUM_MAV_ODID_OPERATOR_ID_TYPE -#define HAVE_ENUM_MAV_ODID_OPERATOR_ID_TYPE -typedef enum MAV_ODID_OPERATOR_ID_TYPE -{ - MAV_ODID_OPERATOR_ID_TYPE_CAA=0, /* CAA (Civil Aviation Authority) registered operator ID. | */ - MAV_ODID_OPERATOR_ID_TYPE_ENUM_END=1, /* | */ -} MAV_ODID_OPERATOR_ID_TYPE; -#endif - -/** @brief */ -#ifndef HAVE_ENUM_MAV_ODID_ARM_STATUS -#define HAVE_ENUM_MAV_ODID_ARM_STATUS -typedef enum MAV_ODID_ARM_STATUS -{ - MAV_ODID_ARM_STATUS_GOOD_TO_ARM=0, /* Passing arming checks. | */ - MAV_ODID_ARM_STATUS_PRE_ARM_FAIL_GENERIC=1, /* Generic arming failure, see error string for details. | */ - MAV_ODID_ARM_STATUS_ENUM_END=2, /* | */ -} MAV_ODID_ARM_STATUS; -#endif - -/** @brief Tune formats (used for vehicle buzzer/tone generation). */ -#ifndef HAVE_ENUM_TUNE_FORMAT -#define HAVE_ENUM_TUNE_FORMAT -typedef enum TUNE_FORMAT -{ - TUNE_FORMAT_QBASIC1_1=1, /* Format is QBasic 1.1 Play: https://www.qbasic.net/en/reference/qb11/Statement/PLAY-006.htm. | */ - TUNE_FORMAT_MML_MODERN=2, /* Format is Modern Music Markup Language (MML): https://en.wikipedia.org/wiki/Music_Macro_Language#Modern_MML. | */ - TUNE_FORMAT_ENUM_END=3, /* | */ -} TUNE_FORMAT; -#endif - -/** @brief Type of AIS vessel, enum duplicated from AIS standard, https://gpsd.gitlab.io/gpsd/AIVDM.html */ -#ifndef HAVE_ENUM_AIS_TYPE -#define HAVE_ENUM_AIS_TYPE -typedef enum AIS_TYPE -{ - AIS_TYPE_UNKNOWN=0, /* Not available (default). | */ - AIS_TYPE_RESERVED_1=1, /* | */ - AIS_TYPE_RESERVED_2=2, /* | */ - AIS_TYPE_RESERVED_3=3, /* | */ - AIS_TYPE_RESERVED_4=4, /* | */ - AIS_TYPE_RESERVED_5=5, /* | */ - AIS_TYPE_RESERVED_6=6, /* | */ - AIS_TYPE_RESERVED_7=7, /* | */ - AIS_TYPE_RESERVED_8=8, /* | */ - AIS_TYPE_RESERVED_9=9, /* | */ - AIS_TYPE_RESERVED_10=10, /* | */ - AIS_TYPE_RESERVED_11=11, /* | */ - AIS_TYPE_RESERVED_12=12, /* | */ - AIS_TYPE_RESERVED_13=13, /* | */ - AIS_TYPE_RESERVED_14=14, /* | */ - AIS_TYPE_RESERVED_15=15, /* | */ - AIS_TYPE_RESERVED_16=16, /* | */ - AIS_TYPE_RESERVED_17=17, /* | */ - AIS_TYPE_RESERVED_18=18, /* | */ - AIS_TYPE_RESERVED_19=19, /* | */ - AIS_TYPE_WIG=20, /* Wing In Ground effect. | */ - AIS_TYPE_WIG_HAZARDOUS_A=21, /* | */ - AIS_TYPE_WIG_HAZARDOUS_B=22, /* | */ - AIS_TYPE_WIG_HAZARDOUS_C=23, /* | */ - AIS_TYPE_WIG_HAZARDOUS_D=24, /* | */ - AIS_TYPE_WIG_RESERVED_1=25, /* | */ - AIS_TYPE_WIG_RESERVED_2=26, /* | */ - AIS_TYPE_WIG_RESERVED_3=27, /* | */ - AIS_TYPE_WIG_RESERVED_4=28, /* | */ - AIS_TYPE_WIG_RESERVED_5=29, /* | */ - AIS_TYPE_FISHING=30, /* | */ - AIS_TYPE_TOWING=31, /* | */ - AIS_TYPE_TOWING_LARGE=32, /* Towing: length exceeds 200m or breadth exceeds 25m. | */ - AIS_TYPE_DREDGING=33, /* Dredging or other underwater ops. | */ - AIS_TYPE_DIVING=34, /* | */ - AIS_TYPE_MILITARY=35, /* | */ - AIS_TYPE_SAILING=36, /* | */ - AIS_TYPE_PLEASURE=37, /* | */ - AIS_TYPE_RESERVED_20=38, /* | */ - AIS_TYPE_RESERVED_21=39, /* | */ - AIS_TYPE_HSC=40, /* High Speed Craft. | */ - AIS_TYPE_HSC_HAZARDOUS_A=41, /* | */ - AIS_TYPE_HSC_HAZARDOUS_B=42, /* | */ - AIS_TYPE_HSC_HAZARDOUS_C=43, /* | */ - AIS_TYPE_HSC_HAZARDOUS_D=44, /* | */ - AIS_TYPE_HSC_RESERVED_1=45, /* | */ - AIS_TYPE_HSC_RESERVED_2=46, /* | */ - AIS_TYPE_HSC_RESERVED_3=47, /* | */ - AIS_TYPE_HSC_RESERVED_4=48, /* | */ - AIS_TYPE_HSC_UNKNOWN=49, /* | */ - AIS_TYPE_PILOT=50, /* | */ - AIS_TYPE_SAR=51, /* Search And Rescue vessel. | */ - AIS_TYPE_TUG=52, /* | */ - AIS_TYPE_PORT_TENDER=53, /* | */ - AIS_TYPE_ANTI_POLLUTION=54, /* Anti-pollution equipment. | */ - AIS_TYPE_LAW_ENFORCEMENT=55, /* | */ - AIS_TYPE_SPARE_LOCAL_1=56, /* | */ - AIS_TYPE_SPARE_LOCAL_2=57, /* | */ - AIS_TYPE_MEDICAL_TRANSPORT=58, /* | */ - AIS_TYPE_NONECOMBATANT=59, /* Noncombatant ship according to RR Resolution No. 18. | */ - AIS_TYPE_PASSENGER=60, /* | */ - AIS_TYPE_PASSENGER_HAZARDOUS_A=61, /* | */ - AIS_TYPE_PASSENGER_HAZARDOUS_B=62, /* | */ - AIS_TYPE_PASSENGER_HAZARDOUS_C=63, /* | */ - AIS_TYPE_PASSENGER_HAZARDOUS_D=64, /* | */ - AIS_TYPE_PASSENGER_RESERVED_1=65, /* | */ - AIS_TYPE_PASSENGER_RESERVED_2=66, /* | */ - AIS_TYPE_PASSENGER_RESERVED_3=67, /* | */ - AIS_TYPE_PASSENGER_RESERVED_4=68, /* | */ - AIS_TYPE_PASSENGER_UNKNOWN=69, /* | */ - AIS_TYPE_CARGO=70, /* | */ - AIS_TYPE_CARGO_HAZARDOUS_A=71, /* | */ - AIS_TYPE_CARGO_HAZARDOUS_B=72, /* | */ - AIS_TYPE_CARGO_HAZARDOUS_C=73, /* | */ - AIS_TYPE_CARGO_HAZARDOUS_D=74, /* | */ - AIS_TYPE_CARGO_RESERVED_1=75, /* | */ - AIS_TYPE_CARGO_RESERVED_2=76, /* | */ - AIS_TYPE_CARGO_RESERVED_3=77, /* | */ - AIS_TYPE_CARGO_RESERVED_4=78, /* | */ - AIS_TYPE_CARGO_UNKNOWN=79, /* | */ - AIS_TYPE_TANKER=80, /* | */ - AIS_TYPE_TANKER_HAZARDOUS_A=81, /* | */ - AIS_TYPE_TANKER_HAZARDOUS_B=82, /* | */ - AIS_TYPE_TANKER_HAZARDOUS_C=83, /* | */ - AIS_TYPE_TANKER_HAZARDOUS_D=84, /* | */ - AIS_TYPE_TANKER_RESERVED_1=85, /* | */ - AIS_TYPE_TANKER_RESERVED_2=86, /* | */ - AIS_TYPE_TANKER_RESERVED_3=87, /* | */ - AIS_TYPE_TANKER_RESERVED_4=88, /* | */ - AIS_TYPE_TANKER_UNKNOWN=89, /* | */ - AIS_TYPE_OTHER=90, /* | */ - AIS_TYPE_OTHER_HAZARDOUS_A=91, /* | */ - AIS_TYPE_OTHER_HAZARDOUS_B=92, /* | */ - AIS_TYPE_OTHER_HAZARDOUS_C=93, /* | */ - AIS_TYPE_OTHER_HAZARDOUS_D=94, /* | */ - AIS_TYPE_OTHER_RESERVED_1=95, /* | */ - AIS_TYPE_OTHER_RESERVED_2=96, /* | */ - AIS_TYPE_OTHER_RESERVED_3=97, /* | */ - AIS_TYPE_OTHER_RESERVED_4=98, /* | */ - AIS_TYPE_OTHER_UNKNOWN=99, /* | */ - AIS_TYPE_ENUM_END=100, /* | */ -} AIS_TYPE; -#endif - -/** @brief Navigational status of AIS vessel, enum duplicated from AIS standard, https://gpsd.gitlab.io/gpsd/AIVDM.html */ -#ifndef HAVE_ENUM_AIS_NAV_STATUS -#define HAVE_ENUM_AIS_NAV_STATUS -typedef enum AIS_NAV_STATUS -{ - UNDER_WAY=0, /* Under way using engine. | */ - AIS_NAV_ANCHORED=1, /* | */ - AIS_NAV_UN_COMMANDED=2, /* | */ - AIS_NAV_RESTRICTED_MANOEUVERABILITY=3, /* | */ - AIS_NAV_DRAUGHT_CONSTRAINED=4, /* | */ - AIS_NAV_MOORED=5, /* | */ - AIS_NAV_AGROUND=6, /* | */ - AIS_NAV_FISHING=7, /* | */ - AIS_NAV_SAILING=8, /* | */ - AIS_NAV_RESERVED_HSC=9, /* | */ - AIS_NAV_RESERVED_WIG=10, /* | */ - AIS_NAV_RESERVED_1=11, /* | */ - AIS_NAV_RESERVED_2=12, /* | */ - AIS_NAV_RESERVED_3=13, /* | */ - AIS_NAV_AIS_SART=14, /* Search And Rescue Transponder. | */ - AIS_NAV_UNKNOWN=15, /* Not available (default). | */ - AIS_NAV_STATUS_ENUM_END=16, /* | */ -} AIS_NAV_STATUS; -#endif - -/** @brief These flags are used in the AIS_VESSEL.fields bitmask to indicate validity of data in the other message fields. When set, the data is valid. */ -#ifndef HAVE_ENUM_AIS_FLAGS -#define HAVE_ENUM_AIS_FLAGS -typedef enum AIS_FLAGS -{ - AIS_FLAGS_POSITION_ACCURACY=1, /* 1 = Position accuracy less than 10m, 0 = position accuracy greater than 10m. | */ - AIS_FLAGS_VALID_COG=2, /* | */ - AIS_FLAGS_VALID_VELOCITY=4, /* | */ - AIS_FLAGS_HIGH_VELOCITY=8, /* 1 = Velocity over 52.5765m/s (102.2 knots) | */ - AIS_FLAGS_VALID_TURN_RATE=16, /* | */ - AIS_FLAGS_TURN_RATE_SIGN_ONLY=32, /* Only the sign of the returned turn rate value is valid, either greater than 5deg/30s or less than -5deg/30s | */ - AIS_FLAGS_VALID_DIMENSIONS=64, /* | */ - AIS_FLAGS_LARGE_BOW_DIMENSION=128, /* Distance to bow is larger than 511m | */ - AIS_FLAGS_LARGE_STERN_DIMENSION=256, /* Distance to stern is larger than 511m | */ - AIS_FLAGS_LARGE_PORT_DIMENSION=512, /* Distance to port side is larger than 63m | */ - AIS_FLAGS_LARGE_STARBOARD_DIMENSION=1024, /* Distance to starboard side is larger than 63m | */ - AIS_FLAGS_VALID_CALLSIGN=2048, /* | */ - AIS_FLAGS_VALID_NAME=4096, /* | */ - AIS_FLAGS_ENUM_END=4097, /* | */ -} AIS_FLAGS; -#endif - -/** @brief List of possible units where failures can be injected. */ -#ifndef HAVE_ENUM_FAILURE_UNIT -#define HAVE_ENUM_FAILURE_UNIT -typedef enum FAILURE_UNIT -{ - FAILURE_UNIT_SENSOR_GYRO=0, /* | */ - FAILURE_UNIT_SENSOR_ACCEL=1, /* | */ - FAILURE_UNIT_SENSOR_MAG=2, /* | */ - FAILURE_UNIT_SENSOR_BARO=3, /* | */ - FAILURE_UNIT_SENSOR_GPS=4, /* | */ - FAILURE_UNIT_SENSOR_OPTICAL_FLOW=5, /* | */ - FAILURE_UNIT_SENSOR_VIO=6, /* | */ - FAILURE_UNIT_SENSOR_DISTANCE_SENSOR=7, /* | */ - FAILURE_UNIT_SENSOR_AIRSPEED=8, /* | */ - FAILURE_UNIT_SYSTEM_BATTERY=100, /* | */ - FAILURE_UNIT_SYSTEM_MOTOR=101, /* | */ - FAILURE_UNIT_SYSTEM_SERVO=102, /* | */ - FAILURE_UNIT_SYSTEM_AVOIDANCE=103, /* | */ - FAILURE_UNIT_SYSTEM_RC_SIGNAL=104, /* | */ - FAILURE_UNIT_SYSTEM_MAVLINK_SIGNAL=105, /* | */ - FAILURE_UNIT_ENUM_END=106, /* | */ -} FAILURE_UNIT; -#endif - -/** @brief List of possible failure type to inject. */ -#ifndef HAVE_ENUM_FAILURE_TYPE -#define HAVE_ENUM_FAILURE_TYPE -typedef enum FAILURE_TYPE -{ - FAILURE_TYPE_OK=0, /* No failure injected, used to reset a previous failure. | */ - FAILURE_TYPE_OFF=1, /* Sets unit off, so completely non-responsive. | */ - FAILURE_TYPE_STUCK=2, /* Unit is stuck e.g. keeps reporting the same value. | */ - FAILURE_TYPE_GARBAGE=3, /* Unit is reporting complete garbage. | */ - FAILURE_TYPE_WRONG=4, /* Unit is consistently wrong. | */ - FAILURE_TYPE_SLOW=5, /* Unit is slow, so e.g. reporting at slower than expected rate. | */ - FAILURE_TYPE_DELAYED=6, /* Data of unit is delayed in time. | */ - FAILURE_TYPE_INTERMITTENT=7, /* Unit is sometimes working, sometimes not. | */ - FAILURE_TYPE_ENUM_END=8, /* | */ -} FAILURE_TYPE; -#endif - -/** @brief */ -#ifndef HAVE_ENUM_NAV_VTOL_LAND_OPTIONS -#define HAVE_ENUM_NAV_VTOL_LAND_OPTIONS -typedef enum NAV_VTOL_LAND_OPTIONS -{ - NAV_VTOL_LAND_OPTIONS_DEFAULT=0, /* Default autopilot landing behaviour. | */ - NAV_VTOL_LAND_OPTIONS_FW_DESCENT=1, /* Descend in fixed wing mode, transitioning to multicopter mode for vertical landing when close to the ground. - The fixed wing descent pattern is at the discretion of the vehicle (e.g. transition altitude, loiter direction, radius, and speed, etc.). - | */ - NAV_VTOL_LAND_OPTIONS_HOVER_DESCENT=2, /* Land in multicopter mode on reaching the landing coordinates (the whole landing is by "hover descent"). | */ - NAV_VTOL_LAND_OPTIONS_ENUM_END=3, /* | */ -} NAV_VTOL_LAND_OPTIONS; -#endif - -/** @brief Winch status flags used in WINCH_STATUS */ -#ifndef HAVE_ENUM_MAV_WINCH_STATUS_FLAG -#define HAVE_ENUM_MAV_WINCH_STATUS_FLAG -typedef enum MAV_WINCH_STATUS_FLAG -{ - MAV_WINCH_STATUS_HEALTHY=1, /* Winch is healthy | */ - MAV_WINCH_STATUS_FULLY_RETRACTED=2, /* Winch line is fully retracted | */ - MAV_WINCH_STATUS_MOVING=4, /* Winch motor is moving | */ - MAV_WINCH_STATUS_CLUTCH_ENGAGED=8, /* Winch clutch is engaged allowing motor to move freely. | */ - MAV_WINCH_STATUS_LOCKED=16, /* Winch is locked by locking mechanism. | */ - MAV_WINCH_STATUS_DROPPING=32, /* Winch is gravity dropping payload. | */ - MAV_WINCH_STATUS_ARRESTING=64, /* Winch is arresting payload descent. | */ - MAV_WINCH_STATUS_GROUND_SENSE=128, /* Winch is using torque measurements to sense the ground. | */ - MAV_WINCH_STATUS_RETRACTING=256, /* Winch is returning to the fully retracted position. | */ - MAV_WINCH_STATUS_REDELIVER=512, /* Winch is redelivering the payload. This is a failover state if the line tension goes above a threshold during RETRACTING. | */ - MAV_WINCH_STATUS_ABANDON_LINE=1024, /* Winch is abandoning the line and possibly payload. Winch unspools the entire calculated line length. This is a failover state from REDELIVER if the number of attempts exceeds a threshold. | */ - MAV_WINCH_STATUS_LOCKING=2048, /* Winch is engaging the locking mechanism. | */ - MAV_WINCH_STATUS_LOAD_LINE=4096, /* Winch is spooling on line. | */ - MAV_WINCH_STATUS_LOAD_PAYLOAD=8192, /* Winch is loading a payload. | */ - MAV_WINCH_STATUS_FLAG_ENUM_END=8193, /* | */ -} MAV_WINCH_STATUS_FLAG; -#endif - -/** @brief */ -#ifndef HAVE_ENUM_MAG_CAL_STATUS -#define HAVE_ENUM_MAG_CAL_STATUS -typedef enum MAG_CAL_STATUS -{ - MAG_CAL_NOT_STARTED=0, /* | */ - MAG_CAL_WAITING_TO_START=1, /* | */ - MAG_CAL_RUNNING_STEP_ONE=2, /* | */ - MAG_CAL_RUNNING_STEP_TWO=3, /* | */ - MAG_CAL_SUCCESS=4, /* | */ - MAG_CAL_FAILED=5, /* | */ - MAG_CAL_BAD_ORIENTATION=6, /* | */ - MAG_CAL_BAD_RADIUS=7, /* | */ - MAG_CAL_STATUS_ENUM_END=8, /* | */ -} MAG_CAL_STATUS; -#endif - -/** @brief Reason for an event error response. */ -#ifndef HAVE_ENUM_MAV_EVENT_ERROR_REASON -#define HAVE_ENUM_MAV_EVENT_ERROR_REASON -typedef enum MAV_EVENT_ERROR_REASON -{ - MAV_EVENT_ERROR_REASON_UNAVAILABLE=0, /* The requested event is not available (anymore). | */ - MAV_EVENT_ERROR_REASON_ENUM_END=1, /* | */ -} MAV_EVENT_ERROR_REASON; -#endif - -/** @brief Flags for CURRENT_EVENT_SEQUENCE. */ -#ifndef HAVE_ENUM_MAV_EVENT_CURRENT_SEQUENCE_FLAGS -#define HAVE_ENUM_MAV_EVENT_CURRENT_SEQUENCE_FLAGS -typedef enum MAV_EVENT_CURRENT_SEQUENCE_FLAGS -{ - MAV_EVENT_CURRENT_SEQUENCE_FLAGS_RESET=1, /* A sequence reset has happened (e.g. vehicle reboot). | */ - MAV_EVENT_CURRENT_SEQUENCE_FLAGS_ENUM_END=2, /* | */ -} MAV_EVENT_CURRENT_SEQUENCE_FLAGS; -#endif - -/** @brief Flags in the HIL_SENSOR message indicate which fields have updated since the last message */ -#ifndef HAVE_ENUM_HIL_SENSOR_UPDATED_FLAGS -#define HAVE_ENUM_HIL_SENSOR_UPDATED_FLAGS -typedef enum HIL_SENSOR_UPDATED_FLAGS -{ - HIL_SENSOR_UPDATED_NONE=0, /* None of the fields in HIL_SENSOR have been updated | */ - HIL_SENSOR_UPDATED_XACC=1, /* The value in the xacc field has been updated | */ - HIL_SENSOR_UPDATED_YACC=2, /* The value in the yacc field has been updated | */ - HIL_SENSOR_UPDATED_ZACC=4, /* The value in the zacc field has been updated | */ - HIL_SENSOR_UPDATED_XGYRO=8, /* The value in the xgyro field has been updated | */ - HIL_SENSOR_UPDATED_YGYRO=16, /* The value in the ygyro field has been updated | */ - HIL_SENSOR_UPDATED_ZGYRO=32, /* The value in the zgyro field has been updated | */ - HIL_SENSOR_UPDATED_XMAG=64, /* The value in the xmag field has been updated | */ - HIL_SENSOR_UPDATED_YMAG=128, /* The value in the ymag field has been updated | */ - HIL_SENSOR_UPDATED_ZMAG=256, /* The value in the zmag field has been updated | */ - HIL_SENSOR_UPDATED_ABS_PRESSURE=512, /* The value in the abs_pressure field has been updated | */ - HIL_SENSOR_UPDATED_DIFF_PRESSURE=1024, /* The value in the diff_pressure field has been updated | */ - HIL_SENSOR_UPDATED_PRESSURE_ALT=2048, /* The value in the pressure_alt field has been updated | */ - HIL_SENSOR_UPDATED_TEMPERATURE=4096, /* The value in the temperature field has been updated | */ - HIL_SENSOR_UPDATED_RESET=2147483648, /* Full reset of attitude/position/velocities/etc was performed in sim (Bit 31). | */ - HIL_SENSOR_UPDATED_FLAGS_ENUM_END=2147483649, /* | */ -} HIL_SENSOR_UPDATED_FLAGS; -#endif - -/** @brief Flags in the HIGHRES_IMU message indicate which fields have updated since the last message */ -#ifndef HAVE_ENUM_HIGHRES_IMU_UPDATED_FLAGS -#define HAVE_ENUM_HIGHRES_IMU_UPDATED_FLAGS -typedef enum HIGHRES_IMU_UPDATED_FLAGS -{ - HIGHRES_IMU_UPDATED_NONE=0, /* None of the fields in HIGHRES_IMU have been updated | */ - HIGHRES_IMU_UPDATED_XACC=1, /* The value in the xacc field has been updated | */ - HIGHRES_IMU_UPDATED_YACC=2, /* The value in the yacc field has been updated | */ - HIGHRES_IMU_UPDATED_ZACC=4, /* The value in the zacc field has been updated since | */ - HIGHRES_IMU_UPDATED_XGYRO=8, /* The value in the xgyro field has been updated | */ - HIGHRES_IMU_UPDATED_YGYRO=16, /* The value in the ygyro field has been updated | */ - HIGHRES_IMU_UPDATED_ZGYRO=32, /* The value in the zgyro field has been updated | */ - HIGHRES_IMU_UPDATED_XMAG=64, /* The value in the xmag field has been updated | */ - HIGHRES_IMU_UPDATED_YMAG=128, /* The value in the ymag field has been updated | */ - HIGHRES_IMU_UPDATED_ZMAG=256, /* The value in the zmag field has been updated | */ - HIGHRES_IMU_UPDATED_ABS_PRESSURE=512, /* The value in the abs_pressure field has been updated | */ - HIGHRES_IMU_UPDATED_DIFF_PRESSURE=1024, /* The value in the diff_pressure field has been updated | */ - HIGHRES_IMU_UPDATED_PRESSURE_ALT=2048, /* The value in the pressure_alt field has been updated | */ - HIGHRES_IMU_UPDATED_TEMPERATURE=4096, /* The value in the temperature field has been updated | */ - HIGHRES_IMU_UPDATED_ALL=65535, /* All fields in HIGHRES_IMU have been updated. | */ - HIGHRES_IMU_UPDATED_FLAGS_ENUM_END=65536, /* | */ -} HIGHRES_IMU_UPDATED_FLAGS; -#endif - -/** @brief */ -#ifndef HAVE_ENUM_CAN_FILTER_OP -#define HAVE_ENUM_CAN_FILTER_OP -typedef enum CAN_FILTER_OP -{ - CAN_FILTER_REPLACE=0, /* | */ - CAN_FILTER_ADD=1, /* | */ - CAN_FILTER_REMOVE=2, /* | */ - CAN_FILTER_OP_ENUM_END=3, /* | */ -} CAN_FILTER_OP; -#endif - -/** @brief MAV FTP error codes (https://mavlink.io/en/services/ftp.html) */ -#ifndef HAVE_ENUM_MAV_FTP_ERR -#define HAVE_ENUM_MAV_FTP_ERR -typedef enum MAV_FTP_ERR -{ - MAV_FTP_ERR_NONE=0, /* None: No error | */ - MAV_FTP_ERR_FAIL=1, /* Fail: Unknown failure | */ - MAV_FTP_ERR_FAILERRNO=2, /* FailErrno: Command failed, Err number sent back in PayloadHeader.data[1]. - This is a file-system error number understood by the server operating system. | */ - MAV_FTP_ERR_INVALIDDATASIZE=3, /* InvalidDataSize: Payload size is invalid | */ - MAV_FTP_ERR_INVALIDSESSION=4, /* InvalidSession: Session is not currently open | */ - MAV_FTP_ERR_NOSESSIONSAVAILABLE=5, /* NoSessionsAvailable: All available sessions are already in use | */ - MAV_FTP_ERR_EOF=6, /* EOF: Offset past end of file for ListDirectory and ReadFile commands | */ - MAV_FTP_ERR_UNKNOWNCOMMAND=7, /* UnknownCommand: Unknown command / opcode | */ - MAV_FTP_ERR_FILEEXISTS=8, /* FileExists: File/directory already exists | */ - MAV_FTP_ERR_FILEPROTECTED=9, /* FileProtected: File/directory is write protected | */ - MAV_FTP_ERR_FILENOTFOUND=10, /* FileNotFound: File/directory not found | */ - MAV_FTP_ERR_ENUM_END=11, /* | */ -} MAV_FTP_ERR; -#endif - -/** @brief MAV FTP opcodes: https://mavlink.io/en/services/ftp.html */ -#ifndef HAVE_ENUM_MAV_FTP_OPCODE -#define HAVE_ENUM_MAV_FTP_OPCODE -typedef enum MAV_FTP_OPCODE -{ - MAV_FTP_OPCODE_NONE=0, /* None. Ignored, always ACKed | */ - MAV_FTP_OPCODE_TERMINATESESSION=1, /* TerminateSession: Terminates open Read session | */ - MAV_FTP_OPCODE_RESETSESSION=2, /* ResetSessions: Terminates all open read sessions | */ - MAV_FTP_OPCODE_LISTDIRECTORY=3, /* ListDirectory. List files and directories in path from offset | */ - MAV_FTP_OPCODE_OPENFILERO=4, /* OpenFileRO: Opens file at path for reading, returns session | */ - MAV_FTP_OPCODE_READFILE=5, /* ReadFile: Reads size bytes from offset in session | */ - MAV_FTP_OPCODE_CREATEFILE=6, /* CreateFile: Creates file at path for writing, returns session | */ - MAV_FTP_OPCODE_WRITEFILE=7, /* WriteFile: Writes size bytes to offset in session | */ - MAV_FTP_OPCODE_REMOVEFILE=8, /* RemoveFile: Remove file at path | */ - MAV_FTP_OPCODE_CREATEDIRECTORY=9, /* CreateDirectory: Creates directory at path | */ - MAV_FTP_OPCODE_REMOVEDIRECTORY=10, /* RemoveDirectory: Removes directory at path. The directory must be empty. | */ - MAV_FTP_OPCODE_OPENFILEWO=11, /* OpenFileWO: Opens file at path for writing, returns session | */ - MAV_FTP_OPCODE_TRUNCATEFILE=12, /* TruncateFile: Truncate file at path to offset length | */ - MAV_FTP_OPCODE_RENAME=13, /* Rename: Rename path1 to path2 | */ - MAV_FTP_OPCODE_CALCFILECRC=14, /* CalcFileCRC32: Calculate CRC32 for file at path | */ - MAV_FTP_OPCODE_BURSTREADFILE=15, /* BurstReadFile: Burst download session file | */ - MAV_FTP_OPCODE_ACK=128, /* ACK: ACK response | */ - MAV_FTP_OPCODE_NAK=129, /* NAK: NAK response | */ - MAV_FTP_OPCODE_ENUM_END=130, /* | */ -} MAV_FTP_OPCODE; -#endif - -/** @brief - States of the mission state machine. - Note that these states are independent of whether the mission is in a mode that can execute mission items or not (is suspended). - They may not all be relevant on all vehicles. - */ -#ifndef HAVE_ENUM_MISSION_STATE -#define HAVE_ENUM_MISSION_STATE -typedef enum MISSION_STATE -{ - MISSION_STATE_UNKNOWN=0, /* The mission status reporting is not supported. | */ - MISSION_STATE_NO_MISSION=1, /* No mission on the vehicle. | */ - MISSION_STATE_NOT_STARTED=2, /* Mission has not started. This is the case after a mission has uploaded but not yet started executing. | */ - MISSION_STATE_ACTIVE=3, /* Mission is active, and will execute mission items when in auto mode. | */ - MISSION_STATE_PAUSED=4, /* Mission is paused when in auto mode. | */ - MISSION_STATE_COMPLETE=5, /* Mission has executed all mission items. | */ - MISSION_STATE_ENUM_END=6, /* | */ -} MISSION_STATE; -#endif - -// MAVLINK VERSION - -#ifndef MAVLINK_VERSION -#define MAVLINK_VERSION 3 -#endif - -#if (MAVLINK_VERSION == 0) -#undef MAVLINK_VERSION -#define MAVLINK_VERSION 3 -#endif - -// MESSAGE DEFINITIONS -#include "./mavlink_msg_sys_status.h" -#include "./mavlink_msg_system_time.h" -#include "./mavlink_msg_ping.h" -#include "./mavlink_msg_change_operator_control.h" -#include "./mavlink_msg_change_operator_control_ack.h" -#include "./mavlink_msg_auth_key.h" -#include "./mavlink_msg_link_node_status.h" -#include "./mavlink_msg_set_mode.h" -#include "./mavlink_msg_param_request_read.h" -#include "./mavlink_msg_param_request_list.h" -#include "./mavlink_msg_param_value.h" -#include "./mavlink_msg_param_set.h" -#include "./mavlink_msg_gps_raw_int.h" -#include "./mavlink_msg_gps_status.h" -#include "./mavlink_msg_scaled_imu.h" -#include "./mavlink_msg_raw_imu.h" -#include "./mavlink_msg_raw_pressure.h" -#include "./mavlink_msg_scaled_pressure.h" -#include "./mavlink_msg_attitude.h" -#include "./mavlink_msg_attitude_quaternion.h" -#include "./mavlink_msg_local_position_ned.h" -#include "./mavlink_msg_global_position_int.h" -#include "./mavlink_msg_rc_channels_scaled.h" -#include "./mavlink_msg_rc_channels_raw.h" -#include "./mavlink_msg_servo_output_raw.h" -#include "./mavlink_msg_mission_request_partial_list.h" -#include "./mavlink_msg_mission_write_partial_list.h" -#include "./mavlink_msg_mission_item.h" -#include "./mavlink_msg_mission_request.h" -#include "./mavlink_msg_mission_set_current.h" -#include "./mavlink_msg_mission_current.h" -#include "./mavlink_msg_mission_request_list.h" -#include "./mavlink_msg_mission_count.h" -#include "./mavlink_msg_mission_clear_all.h" -#include "./mavlink_msg_mission_item_reached.h" -#include "./mavlink_msg_mission_ack.h" -#include "./mavlink_msg_set_gps_global_origin.h" -#include "./mavlink_msg_gps_global_origin.h" -#include "./mavlink_msg_param_map_rc.h" -#include "./mavlink_msg_mission_request_int.h" -#include "./mavlink_msg_safety_set_allowed_area.h" -#include "./mavlink_msg_safety_allowed_area.h" -#include "./mavlink_msg_attitude_quaternion_cov.h" -#include "./mavlink_msg_nav_controller_output.h" -#include "./mavlink_msg_global_position_int_cov.h" -#include "./mavlink_msg_local_position_ned_cov.h" -#include "./mavlink_msg_rc_channels.h" -#include "./mavlink_msg_request_data_stream.h" -#include "./mavlink_msg_data_stream.h" -#include "./mavlink_msg_manual_control.h" -#include "./mavlink_msg_rc_channels_override.h" -#include "./mavlink_msg_mission_item_int.h" -#include "./mavlink_msg_vfr_hud.h" -#include "./mavlink_msg_command_int.h" -#include "./mavlink_msg_command_long.h" -#include "./mavlink_msg_command_ack.h" -#include "./mavlink_msg_command_cancel.h" -#include "./mavlink_msg_manual_setpoint.h" -#include "./mavlink_msg_set_attitude_target.h" -#include "./mavlink_msg_attitude_target.h" -#include "./mavlink_msg_set_position_target_local_ned.h" -#include "./mavlink_msg_position_target_local_ned.h" -#include "./mavlink_msg_set_position_target_global_int.h" -#include "./mavlink_msg_position_target_global_int.h" -#include "./mavlink_msg_local_position_ned_system_global_offset.h" -#include "./mavlink_msg_hil_state.h" -#include "./mavlink_msg_hil_controls.h" -#include "./mavlink_msg_hil_rc_inputs_raw.h" -#include "./mavlink_msg_hil_actuator_controls.h" -#include "./mavlink_msg_optical_flow.h" -#include "./mavlink_msg_global_vision_position_estimate.h" -#include "./mavlink_msg_vision_position_estimate.h" -#include "./mavlink_msg_vision_speed_estimate.h" -#include "./mavlink_msg_vicon_position_estimate.h" -#include "./mavlink_msg_highres_imu.h" -#include "./mavlink_msg_optical_flow_rad.h" -#include "./mavlink_msg_hil_sensor.h" -#include "./mavlink_msg_sim_state.h" -#include "./mavlink_msg_radio_status.h" -#include "./mavlink_msg_file_transfer_protocol.h" -#include "./mavlink_msg_timesync.h" -#include "./mavlink_msg_camera_trigger.h" -#include "./mavlink_msg_hil_gps.h" -#include "./mavlink_msg_hil_optical_flow.h" -#include "./mavlink_msg_hil_state_quaternion.h" -#include "./mavlink_msg_scaled_imu2.h" -#include "./mavlink_msg_log_request_list.h" -#include "./mavlink_msg_log_entry.h" -#include "./mavlink_msg_log_request_data.h" -#include "./mavlink_msg_log_data.h" -#include "./mavlink_msg_log_erase.h" -#include "./mavlink_msg_log_request_end.h" -#include "./mavlink_msg_gps_inject_data.h" -#include "./mavlink_msg_gps2_raw.h" -#include "./mavlink_msg_power_status.h" -#include "./mavlink_msg_serial_control.h" -#include "./mavlink_msg_gps_rtk.h" -#include "./mavlink_msg_gps2_rtk.h" -#include "./mavlink_msg_scaled_imu3.h" -#include "./mavlink_msg_data_transmission_handshake.h" -#include "./mavlink_msg_encapsulated_data.h" -#include "./mavlink_msg_distance_sensor.h" -#include "./mavlink_msg_terrain_request.h" -#include "./mavlink_msg_terrain_data.h" -#include "./mavlink_msg_terrain_check.h" -#include "./mavlink_msg_terrain_report.h" -#include "./mavlink_msg_scaled_pressure2.h" -#include "./mavlink_msg_att_pos_mocap.h" -#include "./mavlink_msg_set_actuator_control_target.h" -#include "./mavlink_msg_actuator_control_target.h" -#include "./mavlink_msg_altitude.h" -#include "./mavlink_msg_resource_request.h" -#include "./mavlink_msg_scaled_pressure3.h" -#include "./mavlink_msg_follow_target.h" -#include "./mavlink_msg_control_system_state.h" -#include "./mavlink_msg_battery_status.h" -#include "./mavlink_msg_autopilot_version.h" -#include "./mavlink_msg_landing_target.h" -#include "./mavlink_msg_fence_status.h" -#include "./mavlink_msg_mag_cal_report.h" -#include "./mavlink_msg_efi_status.h" -#include "./mavlink_msg_estimator_status.h" -#include "./mavlink_msg_wind_cov.h" -#include "./mavlink_msg_gps_input.h" -#include "./mavlink_msg_gps_rtcm_data.h" -#include "./mavlink_msg_high_latency.h" -#include "./mavlink_msg_high_latency2.h" -#include "./mavlink_msg_vibration.h" -#include "./mavlink_msg_home_position.h" -#include "./mavlink_msg_set_home_position.h" -#include "./mavlink_msg_message_interval.h" -#include "./mavlink_msg_extended_sys_state.h" -#include "./mavlink_msg_adsb_vehicle.h" -#include "./mavlink_msg_collision.h" -#include "./mavlink_msg_v2_extension.h" -#include "./mavlink_msg_memory_vect.h" -#include "./mavlink_msg_debug_vect.h" -#include "./mavlink_msg_named_value_float.h" -#include "./mavlink_msg_named_value_int.h" -#include "./mavlink_msg_statustext.h" -#include "./mavlink_msg_debug.h" -#include "./mavlink_msg_setup_signing.h" -#include "./mavlink_msg_button_change.h" -#include "./mavlink_msg_play_tune.h" -#include "./mavlink_msg_camera_information.h" -#include "./mavlink_msg_camera_settings.h" -#include "./mavlink_msg_storage_information.h" -#include "./mavlink_msg_camera_capture_status.h" -#include "./mavlink_msg_camera_image_captured.h" -#include "./mavlink_msg_flight_information.h" -#include "./mavlink_msg_mount_orientation.h" -#include "./mavlink_msg_logging_data.h" -#include "./mavlink_msg_logging_data_acked.h" -#include "./mavlink_msg_logging_ack.h" -#include "./mavlink_msg_video_stream_information.h" -#include "./mavlink_msg_video_stream_status.h" -#include "./mavlink_msg_camera_fov_status.h" -#include "./mavlink_msg_camera_tracking_image_status.h" -#include "./mavlink_msg_camera_tracking_geo_status.h" -#include "./mavlink_msg_gimbal_manager_information.h" -#include "./mavlink_msg_gimbal_manager_status.h" -#include "./mavlink_msg_gimbal_manager_set_attitude.h" -#include "./mavlink_msg_gimbal_device_information.h" -#include "./mavlink_msg_gimbal_device_set_attitude.h" -#include "./mavlink_msg_gimbal_device_attitude_status.h" -#include "./mavlink_msg_autopilot_state_for_gimbal_device.h" -#include "./mavlink_msg_gimbal_manager_set_pitchyaw.h" -#include "./mavlink_msg_gimbal_manager_set_manual_control.h" -#include "./mavlink_msg_esc_info.h" -#include "./mavlink_msg_esc_status.h" -#include "./mavlink_msg_wifi_config_ap.h" -#include "./mavlink_msg_ais_vessel.h" -#include "./mavlink_msg_uavcan_node_status.h" -#include "./mavlink_msg_uavcan_node_info.h" -#include "./mavlink_msg_param_ext_request_read.h" -#include "./mavlink_msg_param_ext_request_list.h" -#include "./mavlink_msg_param_ext_value.h" -#include "./mavlink_msg_param_ext_set.h" -#include "./mavlink_msg_param_ext_ack.h" -#include "./mavlink_msg_obstacle_distance.h" -#include "./mavlink_msg_odometry.h" -#include "./mavlink_msg_trajectory_representation_waypoints.h" -#include "./mavlink_msg_trajectory_representation_bezier.h" -#include "./mavlink_msg_cellular_status.h" -#include "./mavlink_msg_isbd_link_status.h" -#include "./mavlink_msg_cellular_config.h" -#include "./mavlink_msg_raw_rpm.h" -#include "./mavlink_msg_utm_global_position.h" -#include "./mavlink_msg_debug_float_array.h" -#include "./mavlink_msg_orbit_execution_status.h" -#include "./mavlink_msg_smart_battery_info.h" -#include "./mavlink_msg_generator_status.h" -#include "./mavlink_msg_actuator_output_status.h" -#include "./mavlink_msg_time_estimate_to_target.h" -#include "./mavlink_msg_tunnel.h" -#include "./mavlink_msg_can_frame.h" -#include "./mavlink_msg_onboard_computer_status.h" -#include "./mavlink_msg_component_information.h" -#include "./mavlink_msg_component_metadata.h" -#include "./mavlink_msg_play_tune_v2.h" -#include "./mavlink_msg_supported_tunes.h" -#include "./mavlink_msg_event.h" -#include "./mavlink_msg_current_event_sequence.h" -#include "./mavlink_msg_request_event.h" -#include "./mavlink_msg_response_event_error.h" -#include "./mavlink_msg_canfd_frame.h" -#include "./mavlink_msg_can_filter_modify.h" -#include "./mavlink_msg_wheel_distance.h" -#include "./mavlink_msg_winch_status.h" -#include "./mavlink_msg_open_drone_id_basic_id.h" -#include "./mavlink_msg_open_drone_id_location.h" -#include "./mavlink_msg_open_drone_id_authentication.h" -#include "./mavlink_msg_open_drone_id_self_id.h" -#include "./mavlink_msg_open_drone_id_system.h" -#include "./mavlink_msg_open_drone_id_operator_id.h" -#include "./mavlink_msg_open_drone_id_message_pack.h" -#include "./mavlink_msg_open_drone_id_arm_status.h" -#include "./mavlink_msg_open_drone_id_system_update.h" -#include "./mavlink_msg_hygrometer_sensor.h" - -// base include -#include "../standard/standard.h" - - -#if MAVLINK_COMMON_XML_HASH == MAVLINK_PRIMARY_XML_HASH -# define MAVLINK_MESSAGE_INFO {MAVLINK_MESSAGE_INFO_HEARTBEAT, MAVLINK_MESSAGE_INFO_SYS_STATUS, MAVLINK_MESSAGE_INFO_SYSTEM_TIME, MAVLINK_MESSAGE_INFO_PING, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL_ACK, MAVLINK_MESSAGE_INFO_AUTH_KEY, MAVLINK_MESSAGE_INFO_LINK_NODE_STATUS, MAVLINK_MESSAGE_INFO_SET_MODE, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_READ, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_LIST, MAVLINK_MESSAGE_INFO_PARAM_VALUE, MAVLINK_MESSAGE_INFO_PARAM_SET, MAVLINK_MESSAGE_INFO_GPS_RAW_INT, MAVLINK_MESSAGE_INFO_GPS_STATUS, MAVLINK_MESSAGE_INFO_SCALED_IMU, MAVLINK_MESSAGE_INFO_RAW_IMU, MAVLINK_MESSAGE_INFO_RAW_PRESSURE, MAVLINK_MESSAGE_INFO_SCALED_PRESSURE, MAVLINK_MESSAGE_INFO_ATTITUDE, MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT, MAVLINK_MESSAGE_INFO_RC_CHANNELS_SCALED, MAVLINK_MESSAGE_INFO_RC_CHANNELS_RAW, MAVLINK_MESSAGE_INFO_SERVO_OUTPUT_RAW, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_WRITE_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_ITEM, MAVLINK_MESSAGE_INFO_MISSION_REQUEST, MAVLINK_MESSAGE_INFO_MISSION_SET_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_LIST, MAVLINK_MESSAGE_INFO_MISSION_COUNT, MAVLINK_MESSAGE_INFO_MISSION_CLEAR_ALL, MAVLINK_MESSAGE_INFO_MISSION_ITEM_REACHED, MAVLINK_MESSAGE_INFO_MISSION_ACK, MAVLINK_MESSAGE_INFO_SET_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_PARAM_MAP_RC, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_INT, MAVLINK_MESSAGE_INFO_SAFETY_SET_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SAFETY_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION_COV, MAVLINK_MESSAGE_INFO_NAV_CONTROLLER_OUTPUT, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT_COV, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED_COV, MAVLINK_MESSAGE_INFO_RC_CHANNELS, MAVLINK_MESSAGE_INFO_REQUEST_DATA_STREAM, MAVLINK_MESSAGE_INFO_DATA_STREAM, MAVLINK_MESSAGE_INFO_MANUAL_CONTROL, MAVLINK_MESSAGE_INFO_RC_CHANNELS_OVERRIDE, MAVLINK_MESSAGE_INFO_MISSION_ITEM_INT, MAVLINK_MESSAGE_INFO_VFR_HUD, MAVLINK_MESSAGE_INFO_COMMAND_INT, MAVLINK_MESSAGE_INFO_COMMAND_LONG, MAVLINK_MESSAGE_INFO_COMMAND_ACK, MAVLINK_MESSAGE_INFO_COMMAND_CANCEL, MAVLINK_MESSAGE_INFO_MANUAL_SETPOINT, MAVLINK_MESSAGE_INFO_SET_ATTITUDE_TARGET, MAVLINK_MESSAGE_INFO_ATTITUDE_TARGET, MAVLINK_MESSAGE_INFO_SET_POSITION_TARGET_LOCAL_NED, MAVLINK_MESSAGE_INFO_POSITION_TARGET_LOCAL_NED, MAVLINK_MESSAGE_INFO_SET_POSITION_TARGET_GLOBAL_INT, MAVLINK_MESSAGE_INFO_POSITION_TARGET_GLOBAL_INT, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET, MAVLINK_MESSAGE_INFO_HIL_STATE, MAVLINK_MESSAGE_INFO_HIL_CONTROLS, MAVLINK_MESSAGE_INFO_HIL_RC_INPUTS_RAW, MAVLINK_MESSAGE_INFO_HIL_ACTUATOR_CONTROLS, MAVLINK_MESSAGE_INFO_OPTICAL_FLOW, MAVLINK_MESSAGE_INFO_GLOBAL_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_SPEED_ESTIMATE, MAVLINK_MESSAGE_INFO_VICON_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_HIGHRES_IMU, MAVLINK_MESSAGE_INFO_OPTICAL_FLOW_RAD, MAVLINK_MESSAGE_INFO_HIL_SENSOR, MAVLINK_MESSAGE_INFO_SIM_STATE, MAVLINK_MESSAGE_INFO_RADIO_STATUS, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_PROTOCOL, MAVLINK_MESSAGE_INFO_TIMESYNC, MAVLINK_MESSAGE_INFO_CAMERA_TRIGGER, MAVLINK_MESSAGE_INFO_HIL_GPS, MAVLINK_MESSAGE_INFO_HIL_OPTICAL_FLOW, MAVLINK_MESSAGE_INFO_HIL_STATE_QUATERNION, MAVLINK_MESSAGE_INFO_SCALED_IMU2, MAVLINK_MESSAGE_INFO_LOG_REQUEST_LIST, MAVLINK_MESSAGE_INFO_LOG_ENTRY, MAVLINK_MESSAGE_INFO_LOG_REQUEST_DATA, MAVLINK_MESSAGE_INFO_LOG_DATA, MAVLINK_MESSAGE_INFO_LOG_ERASE, MAVLINK_MESSAGE_INFO_LOG_REQUEST_END, MAVLINK_MESSAGE_INFO_GPS_INJECT_DATA, MAVLINK_MESSAGE_INFO_GPS2_RAW, MAVLINK_MESSAGE_INFO_POWER_STATUS, MAVLINK_MESSAGE_INFO_SERIAL_CONTROL, MAVLINK_MESSAGE_INFO_GPS_RTK, MAVLINK_MESSAGE_INFO_GPS2_RTK, MAVLINK_MESSAGE_INFO_SCALED_IMU3, MAVLINK_MESSAGE_INFO_DATA_TRANSMISSION_HANDSHAKE, MAVLINK_MESSAGE_INFO_ENCAPSULATED_DATA, MAVLINK_MESSAGE_INFO_DISTANCE_SENSOR, MAVLINK_MESSAGE_INFO_TERRAIN_REQUEST, MAVLINK_MESSAGE_INFO_TERRAIN_DATA, MAVLINK_MESSAGE_INFO_TERRAIN_CHECK, MAVLINK_MESSAGE_INFO_TERRAIN_REPORT, MAVLINK_MESSAGE_INFO_SCALED_PRESSURE2, MAVLINK_MESSAGE_INFO_ATT_POS_MOCAP, MAVLINK_MESSAGE_INFO_SET_ACTUATOR_CONTROL_TARGET, MAVLINK_MESSAGE_INFO_ACTUATOR_CONTROL_TARGET, MAVLINK_MESSAGE_INFO_ALTITUDE, MAVLINK_MESSAGE_INFO_RESOURCE_REQUEST, MAVLINK_MESSAGE_INFO_SCALED_PRESSURE3, MAVLINK_MESSAGE_INFO_FOLLOW_TARGET, MAVLINK_MESSAGE_INFO_CONTROL_SYSTEM_STATE, MAVLINK_MESSAGE_INFO_BATTERY_STATUS, MAVLINK_MESSAGE_INFO_AUTOPILOT_VERSION, MAVLINK_MESSAGE_INFO_LANDING_TARGET, MAVLINK_MESSAGE_INFO_FENCE_STATUS, MAVLINK_MESSAGE_INFO_MAG_CAL_REPORT, MAVLINK_MESSAGE_INFO_EFI_STATUS, MAVLINK_MESSAGE_INFO_ESTIMATOR_STATUS, MAVLINK_MESSAGE_INFO_WIND_COV, MAVLINK_MESSAGE_INFO_GPS_INPUT, MAVLINK_MESSAGE_INFO_GPS_RTCM_DATA, MAVLINK_MESSAGE_INFO_HIGH_LATENCY, MAVLINK_MESSAGE_INFO_HIGH_LATENCY2, MAVLINK_MESSAGE_INFO_VIBRATION, MAVLINK_MESSAGE_INFO_HOME_POSITION, MAVLINK_MESSAGE_INFO_SET_HOME_POSITION, MAVLINK_MESSAGE_INFO_MESSAGE_INTERVAL, MAVLINK_MESSAGE_INFO_EXTENDED_SYS_STATE, MAVLINK_MESSAGE_INFO_ADSB_VEHICLE, MAVLINK_MESSAGE_INFO_COLLISION, MAVLINK_MESSAGE_INFO_V2_EXTENSION, MAVLINK_MESSAGE_INFO_MEMORY_VECT, MAVLINK_MESSAGE_INFO_DEBUG_VECT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_FLOAT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_INT, MAVLINK_MESSAGE_INFO_STATUSTEXT, MAVLINK_MESSAGE_INFO_DEBUG, MAVLINK_MESSAGE_INFO_SETUP_SIGNING, MAVLINK_MESSAGE_INFO_BUTTON_CHANGE, MAVLINK_MESSAGE_INFO_PLAY_TUNE, MAVLINK_MESSAGE_INFO_CAMERA_INFORMATION, MAVLINK_MESSAGE_INFO_CAMERA_SETTINGS, MAVLINK_MESSAGE_INFO_STORAGE_INFORMATION, MAVLINK_MESSAGE_INFO_CAMERA_CAPTURE_STATUS, MAVLINK_MESSAGE_INFO_CAMERA_IMAGE_CAPTURED, MAVLINK_MESSAGE_INFO_FLIGHT_INFORMATION, MAVLINK_MESSAGE_INFO_MOUNT_ORIENTATION, MAVLINK_MESSAGE_INFO_LOGGING_DATA, MAVLINK_MESSAGE_INFO_LOGGING_DATA_ACKED, MAVLINK_MESSAGE_INFO_LOGGING_ACK, MAVLINK_MESSAGE_INFO_VIDEO_STREAM_INFORMATION, MAVLINK_MESSAGE_INFO_VIDEO_STREAM_STATUS, MAVLINK_MESSAGE_INFO_CAMERA_FOV_STATUS, MAVLINK_MESSAGE_INFO_CAMERA_TRACKING_IMAGE_STATUS, MAVLINK_MESSAGE_INFO_CAMERA_TRACKING_GEO_STATUS, MAVLINK_MESSAGE_INFO_GIMBAL_MANAGER_INFORMATION, MAVLINK_MESSAGE_INFO_GIMBAL_MANAGER_STATUS, MAVLINK_MESSAGE_INFO_GIMBAL_MANAGER_SET_ATTITUDE, MAVLINK_MESSAGE_INFO_GIMBAL_DEVICE_INFORMATION, MAVLINK_MESSAGE_INFO_GIMBAL_DEVICE_SET_ATTITUDE, MAVLINK_MESSAGE_INFO_GIMBAL_DEVICE_ATTITUDE_STATUS, MAVLINK_MESSAGE_INFO_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE, MAVLINK_MESSAGE_INFO_GIMBAL_MANAGER_SET_PITCHYAW, MAVLINK_MESSAGE_INFO_GIMBAL_MANAGER_SET_MANUAL_CONTROL, MAVLINK_MESSAGE_INFO_ESC_INFO, MAVLINK_MESSAGE_INFO_ESC_STATUS, MAVLINK_MESSAGE_INFO_WIFI_CONFIG_AP, MAVLINK_MESSAGE_INFO_PROTOCOL_VERSION, MAVLINK_MESSAGE_INFO_AIS_VESSEL, MAVLINK_MESSAGE_INFO_UAVCAN_NODE_STATUS, MAVLINK_MESSAGE_INFO_UAVCAN_NODE_INFO, MAVLINK_MESSAGE_INFO_PARAM_EXT_REQUEST_READ, MAVLINK_MESSAGE_INFO_PARAM_EXT_REQUEST_LIST, MAVLINK_MESSAGE_INFO_PARAM_EXT_VALUE, MAVLINK_MESSAGE_INFO_PARAM_EXT_SET, MAVLINK_MESSAGE_INFO_PARAM_EXT_ACK, MAVLINK_MESSAGE_INFO_OBSTACLE_DISTANCE, MAVLINK_MESSAGE_INFO_ODOMETRY, MAVLINK_MESSAGE_INFO_TRAJECTORY_REPRESENTATION_WAYPOINTS, MAVLINK_MESSAGE_INFO_TRAJECTORY_REPRESENTATION_BEZIER, MAVLINK_MESSAGE_INFO_CELLULAR_STATUS, MAVLINK_MESSAGE_INFO_ISBD_LINK_STATUS, MAVLINK_MESSAGE_INFO_CELLULAR_CONFIG, MAVLINK_MESSAGE_INFO_RAW_RPM, MAVLINK_MESSAGE_INFO_UTM_GLOBAL_POSITION, MAVLINK_MESSAGE_INFO_DEBUG_FLOAT_ARRAY, MAVLINK_MESSAGE_INFO_ORBIT_EXECUTION_STATUS, MAVLINK_MESSAGE_INFO_SMART_BATTERY_INFO, MAVLINK_MESSAGE_INFO_GENERATOR_STATUS, MAVLINK_MESSAGE_INFO_ACTUATOR_OUTPUT_STATUS, MAVLINK_MESSAGE_INFO_TIME_ESTIMATE_TO_TARGET, MAVLINK_MESSAGE_INFO_TUNNEL, MAVLINK_MESSAGE_INFO_CAN_FRAME, MAVLINK_MESSAGE_INFO_CANFD_FRAME, MAVLINK_MESSAGE_INFO_CAN_FILTER_MODIFY, MAVLINK_MESSAGE_INFO_ONBOARD_COMPUTER_STATUS, MAVLINK_MESSAGE_INFO_COMPONENT_INFORMATION, MAVLINK_MESSAGE_INFO_COMPONENT_METADATA, MAVLINK_MESSAGE_INFO_PLAY_TUNE_V2, MAVLINK_MESSAGE_INFO_SUPPORTED_TUNES, MAVLINK_MESSAGE_INFO_EVENT, MAVLINK_MESSAGE_INFO_CURRENT_EVENT_SEQUENCE, MAVLINK_MESSAGE_INFO_REQUEST_EVENT, MAVLINK_MESSAGE_INFO_RESPONSE_EVENT_ERROR, MAVLINK_MESSAGE_INFO_WHEEL_DISTANCE, MAVLINK_MESSAGE_INFO_WINCH_STATUS, MAVLINK_MESSAGE_INFO_OPEN_DRONE_ID_BASIC_ID, MAVLINK_MESSAGE_INFO_OPEN_DRONE_ID_LOCATION, MAVLINK_MESSAGE_INFO_OPEN_DRONE_ID_AUTHENTICATION, MAVLINK_MESSAGE_INFO_OPEN_DRONE_ID_SELF_ID, MAVLINK_MESSAGE_INFO_OPEN_DRONE_ID_SYSTEM, MAVLINK_MESSAGE_INFO_OPEN_DRONE_ID_OPERATOR_ID, MAVLINK_MESSAGE_INFO_OPEN_DRONE_ID_MESSAGE_PACK, MAVLINK_MESSAGE_INFO_OPEN_DRONE_ID_ARM_STATUS, MAVLINK_MESSAGE_INFO_OPEN_DRONE_ID_SYSTEM_UPDATE, MAVLINK_MESSAGE_INFO_HYGROMETER_SENSOR} -# define MAVLINK_MESSAGE_NAMES {{ "ACTUATOR_CONTROL_TARGET", 140 }, { "ACTUATOR_OUTPUT_STATUS", 375 }, { "ADSB_VEHICLE", 246 }, { "AIS_VESSEL", 301 }, { "ALTITUDE", 141 }, { "ATTITUDE", 30 }, { "ATTITUDE_QUATERNION", 31 }, { "ATTITUDE_QUATERNION_COV", 61 }, { "ATTITUDE_TARGET", 83 }, { "ATT_POS_MOCAP", 138 }, { "AUTH_KEY", 7 }, { "AUTOPILOT_STATE_FOR_GIMBAL_DEVICE", 286 }, { "AUTOPILOT_VERSION", 148 }, { "BATTERY_STATUS", 147 }, { "BUTTON_CHANGE", 257 }, { "CAMERA_CAPTURE_STATUS", 262 }, { "CAMERA_FOV_STATUS", 271 }, { "CAMERA_IMAGE_CAPTURED", 263 }, { "CAMERA_INFORMATION", 259 }, { "CAMERA_SETTINGS", 260 }, { "CAMERA_TRACKING_GEO_STATUS", 276 }, { "CAMERA_TRACKING_IMAGE_STATUS", 275 }, { "CAMERA_TRIGGER", 112 }, { "CANFD_FRAME", 387 }, { "CAN_FILTER_MODIFY", 388 }, { "CAN_FRAME", 386 }, { "CELLULAR_CONFIG", 336 }, { "CELLULAR_STATUS", 334 }, { "CHANGE_OPERATOR_CONTROL", 5 }, { "CHANGE_OPERATOR_CONTROL_ACK", 6 }, { "COLLISION", 247 }, { "COMMAND_ACK", 77 }, { "COMMAND_CANCEL", 80 }, { "COMMAND_INT", 75 }, { "COMMAND_LONG", 76 }, { "COMPONENT_INFORMATION", 395 }, { "COMPONENT_METADATA", 397 }, { "CONTROL_SYSTEM_STATE", 146 }, { "CURRENT_EVENT_SEQUENCE", 411 }, { "DATA_STREAM", 67 }, { "DATA_TRANSMISSION_HANDSHAKE", 130 }, { "DEBUG", 254 }, { "DEBUG_FLOAT_ARRAY", 350 }, { "DEBUG_VECT", 250 }, { "DISTANCE_SENSOR", 132 }, { "EFI_STATUS", 225 }, { "ENCAPSULATED_DATA", 131 }, { "ESC_INFO", 290 }, { "ESC_STATUS", 291 }, { "ESTIMATOR_STATUS", 230 }, { "EVENT", 410 }, { "EXTENDED_SYS_STATE", 245 }, { "FENCE_STATUS", 162 }, { "FILE_TRANSFER_PROTOCOL", 110 }, { "FLIGHT_INFORMATION", 264 }, { "FOLLOW_TARGET", 144 }, { "GENERATOR_STATUS", 373 }, { "GIMBAL_DEVICE_ATTITUDE_STATUS", 285 }, { "GIMBAL_DEVICE_INFORMATION", 283 }, { "GIMBAL_DEVICE_SET_ATTITUDE", 284 }, { "GIMBAL_MANAGER_INFORMATION", 280 }, { "GIMBAL_MANAGER_SET_ATTITUDE", 282 }, { "GIMBAL_MANAGER_SET_MANUAL_CONTROL", 288 }, { "GIMBAL_MANAGER_SET_PITCHYAW", 287 }, { "GIMBAL_MANAGER_STATUS", 281 }, { "GLOBAL_POSITION_INT", 33 }, { "GLOBAL_POSITION_INT_COV", 63 }, { "GLOBAL_VISION_POSITION_ESTIMATE", 101 }, { "GPS2_RAW", 124 }, { "GPS2_RTK", 128 }, { "GPS_GLOBAL_ORIGIN", 49 }, { "GPS_INJECT_DATA", 123 }, { "GPS_INPUT", 232 }, { "GPS_RAW_INT", 24 }, { "GPS_RTCM_DATA", 233 }, { "GPS_RTK", 127 }, { "GPS_STATUS", 25 }, { "HEARTBEAT", 0 }, { "HIGHRES_IMU", 105 }, { "HIGH_LATENCY", 234 }, { "HIGH_LATENCY2", 235 }, { "HIL_ACTUATOR_CONTROLS", 93 }, { "HIL_CONTROLS", 91 }, { "HIL_GPS", 113 }, { "HIL_OPTICAL_FLOW", 114 }, { "HIL_RC_INPUTS_RAW", 92 }, { "HIL_SENSOR", 107 }, { "HIL_STATE", 90 }, { "HIL_STATE_QUATERNION", 115 }, { "HOME_POSITION", 242 }, { "HYGROMETER_SENSOR", 12920 }, { "ISBD_LINK_STATUS", 335 }, { "LANDING_TARGET", 149 }, { "LINK_NODE_STATUS", 8 }, { "LOCAL_POSITION_NED", 32 }, { "LOCAL_POSITION_NED_COV", 64 }, { "LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET", 89 }, { "LOGGING_ACK", 268 }, { "LOGGING_DATA", 266 }, { "LOGGING_DATA_ACKED", 267 }, { "LOG_DATA", 120 }, { "LOG_ENTRY", 118 }, { "LOG_ERASE", 121 }, { "LOG_REQUEST_DATA", 119 }, { "LOG_REQUEST_END", 122 }, { "LOG_REQUEST_LIST", 117 }, { "MAG_CAL_REPORT", 192 }, { "MANUAL_CONTROL", 69 }, { "MANUAL_SETPOINT", 81 }, { "MEMORY_VECT", 249 }, { "MESSAGE_INTERVAL", 244 }, { "MISSION_ACK", 47 }, { "MISSION_CLEAR_ALL", 45 }, { "MISSION_COUNT", 44 }, { "MISSION_CURRENT", 42 }, { "MISSION_ITEM", 39 }, { "MISSION_ITEM_INT", 73 }, { "MISSION_ITEM_REACHED", 46 }, { "MISSION_REQUEST", 40 }, { "MISSION_REQUEST_INT", 51 }, { "MISSION_REQUEST_LIST", 43 }, { "MISSION_REQUEST_PARTIAL_LIST", 37 }, { "MISSION_SET_CURRENT", 41 }, { "MISSION_WRITE_PARTIAL_LIST", 38 }, { "MOUNT_ORIENTATION", 265 }, { "NAMED_VALUE_FLOAT", 251 }, { "NAMED_VALUE_INT", 252 }, { "NAV_CONTROLLER_OUTPUT", 62 }, { "OBSTACLE_DISTANCE", 330 }, { "ODOMETRY", 331 }, { "ONBOARD_COMPUTER_STATUS", 390 }, { "OPEN_DRONE_ID_ARM_STATUS", 12918 }, { "OPEN_DRONE_ID_AUTHENTICATION", 12902 }, { "OPEN_DRONE_ID_BASIC_ID", 12900 }, { "OPEN_DRONE_ID_LOCATION", 12901 }, { "OPEN_DRONE_ID_MESSAGE_PACK", 12915 }, { "OPEN_DRONE_ID_OPERATOR_ID", 12905 }, { "OPEN_DRONE_ID_SELF_ID", 12903 }, { "OPEN_DRONE_ID_SYSTEM", 12904 }, { "OPEN_DRONE_ID_SYSTEM_UPDATE", 12919 }, { "OPTICAL_FLOW", 100 }, { "OPTICAL_FLOW_RAD", 106 }, { "ORBIT_EXECUTION_STATUS", 360 }, { "PARAM_EXT_ACK", 324 }, { "PARAM_EXT_REQUEST_LIST", 321 }, { "PARAM_EXT_REQUEST_READ", 320 }, { "PARAM_EXT_SET", 323 }, { "PARAM_EXT_VALUE", 322 }, { "PARAM_MAP_RC", 50 }, { "PARAM_REQUEST_LIST", 21 }, { "PARAM_REQUEST_READ", 20 }, { "PARAM_SET", 23 }, { "PARAM_VALUE", 22 }, { "PING", 4 }, { "PLAY_TUNE", 258 }, { "PLAY_TUNE_V2", 400 }, { "POSITION_TARGET_GLOBAL_INT", 87 }, { "POSITION_TARGET_LOCAL_NED", 85 }, { "POWER_STATUS", 125 }, { "PROTOCOL_VERSION", 300 }, { "RADIO_STATUS", 109 }, { "RAW_IMU", 27 }, { "RAW_PRESSURE", 28 }, { "RAW_RPM", 339 }, { "RC_CHANNELS", 65 }, { "RC_CHANNELS_OVERRIDE", 70 }, { "RC_CHANNELS_RAW", 35 }, { "RC_CHANNELS_SCALED", 34 }, { "REQUEST_DATA_STREAM", 66 }, { "REQUEST_EVENT", 412 }, { "RESOURCE_REQUEST", 142 }, { "RESPONSE_EVENT_ERROR", 413 }, { "SAFETY_ALLOWED_AREA", 55 }, { "SAFETY_SET_ALLOWED_AREA", 54 }, { "SCALED_IMU", 26 }, { "SCALED_IMU2", 116 }, { "SCALED_IMU3", 129 }, { "SCALED_PRESSURE", 29 }, { "SCALED_PRESSURE2", 137 }, { "SCALED_PRESSURE3", 143 }, { "SERIAL_CONTROL", 126 }, { "SERVO_OUTPUT_RAW", 36 }, { "SETUP_SIGNING", 256 }, { "SET_ACTUATOR_CONTROL_TARGET", 139 }, { "SET_ATTITUDE_TARGET", 82 }, { "SET_GPS_GLOBAL_ORIGIN", 48 }, { "SET_HOME_POSITION", 243 }, { "SET_MODE", 11 }, { "SET_POSITION_TARGET_GLOBAL_INT", 86 }, { "SET_POSITION_TARGET_LOCAL_NED", 84 }, { "SIM_STATE", 108 }, { "SMART_BATTERY_INFO", 370 }, { "STATUSTEXT", 253 }, { "STORAGE_INFORMATION", 261 }, { "SUPPORTED_TUNES", 401 }, { "SYSTEM_TIME", 2 }, { "SYS_STATUS", 1 }, { "TERRAIN_CHECK", 135 }, { "TERRAIN_DATA", 134 }, { "TERRAIN_REPORT", 136 }, { "TERRAIN_REQUEST", 133 }, { "TIMESYNC", 111 }, { "TIME_ESTIMATE_TO_TARGET", 380 }, { "TRAJECTORY_REPRESENTATION_BEZIER", 333 }, { "TRAJECTORY_REPRESENTATION_WAYPOINTS", 332 }, { "TUNNEL", 385 }, { "UAVCAN_NODE_INFO", 311 }, { "UAVCAN_NODE_STATUS", 310 }, { "UTM_GLOBAL_POSITION", 340 }, { "V2_EXTENSION", 248 }, { "VFR_HUD", 74 }, { "VIBRATION", 241 }, { "VICON_POSITION_ESTIMATE", 104 }, { "VIDEO_STREAM_INFORMATION", 269 }, { "VIDEO_STREAM_STATUS", 270 }, { "VISION_POSITION_ESTIMATE", 102 }, { "VISION_SPEED_ESTIMATE", 103 }, { "WHEEL_DISTANCE", 9000 }, { "WIFI_CONFIG_AP", 299 }, { "WINCH_STATUS", 9005 }, { "WIND_COV", 231 }} -# if MAVLINK_COMMAND_24BIT -# include "../mavlink_get_info.h" -# endif -#endif - -#ifdef __cplusplus -} -#endif // __cplusplus -#endif // MAVLINK_COMMON_H diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink.h deleted file mode 100644 index acee1aef..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink.h +++ /dev/null @@ -1,34 +0,0 @@ -/** @file - * @brief MAVLink comm protocol built from common.xml - * @see http://mavlink.org - */ -#pragma once -#ifndef MAVLINK_H -#define MAVLINK_H - -#define MAVLINK_PRIMARY_XML_HASH -2384891800141893948 - -#ifndef MAVLINK_STX -#define MAVLINK_STX 253 -#endif - -#ifndef MAVLINK_ENDIAN -#define MAVLINK_ENDIAN MAVLINK_LITTLE_ENDIAN -#endif - -#ifndef MAVLINK_ALIGNED_FIELDS -#define MAVLINK_ALIGNED_FIELDS 1 -#endif - -#ifndef MAVLINK_CRC_EXTRA -#define MAVLINK_CRC_EXTRA 1 -#endif - -#ifndef MAVLINK_COMMAND_24BIT -#define MAVLINK_COMMAND_24BIT 1 -#endif - -#include "version.h" -#include "common.h" - -#endif // MAVLINK_H diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_actuator_control_target.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_actuator_control_target.h deleted file mode 100644 index c5ad9f65..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_actuator_control_target.h +++ /dev/null @@ -1,255 +0,0 @@ -#pragma once -// MESSAGE ACTUATOR_CONTROL_TARGET PACKING - -#define MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET 140 - - -typedef struct __mavlink_actuator_control_target_t { - uint64_t time_usec; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/ - float controls[8]; /*< Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs.*/ - uint8_t group_mlx; /*< Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances.*/ -} mavlink_actuator_control_target_t; - -#define MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN 41 -#define MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_MIN_LEN 41 -#define MAVLINK_MSG_ID_140_LEN 41 -#define MAVLINK_MSG_ID_140_MIN_LEN 41 - -#define MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_CRC 181 -#define MAVLINK_MSG_ID_140_CRC 181 - -#define MAVLINK_MSG_ACTUATOR_CONTROL_TARGET_FIELD_CONTROLS_LEN 8 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_ACTUATOR_CONTROL_TARGET { \ - 140, \ - "ACTUATOR_CONTROL_TARGET", \ - 3, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_actuator_control_target_t, time_usec) }, \ - { "group_mlx", NULL, MAVLINK_TYPE_UINT8_T, 0, 40, offsetof(mavlink_actuator_control_target_t, group_mlx) }, \ - { "controls", NULL, MAVLINK_TYPE_FLOAT, 8, 8, offsetof(mavlink_actuator_control_target_t, controls) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_ACTUATOR_CONTROL_TARGET { \ - "ACTUATOR_CONTROL_TARGET", \ - 3, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_actuator_control_target_t, time_usec) }, \ - { "group_mlx", NULL, MAVLINK_TYPE_UINT8_T, 0, 40, offsetof(mavlink_actuator_control_target_t, group_mlx) }, \ - { "controls", NULL, MAVLINK_TYPE_FLOAT, 8, 8, offsetof(mavlink_actuator_control_target_t, controls) }, \ - } \ -} -#endif - -/** - * @brief Pack a actuator_control_target message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @param group_mlx Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances. - * @param controls Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_actuator_control_target_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint64_t time_usec, uint8_t group_mlx, const float *controls) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint8_t(buf, 40, group_mlx); - _mav_put_float_array(buf, 8, controls, 8); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN); -#else - mavlink_actuator_control_target_t packet; - packet.time_usec = time_usec; - packet.group_mlx = group_mlx; - mav_array_memcpy(packet.controls, controls, sizeof(float)*8); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_MIN_LEN, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_CRC); -} - -/** - * @brief Pack a actuator_control_target message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @param group_mlx Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances. - * @param controls Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_actuator_control_target_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint64_t time_usec,uint8_t group_mlx,const float *controls) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint8_t(buf, 40, group_mlx); - _mav_put_float_array(buf, 8, controls, 8); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN); -#else - mavlink_actuator_control_target_t packet; - packet.time_usec = time_usec; - packet.group_mlx = group_mlx; - mav_array_memcpy(packet.controls, controls, sizeof(float)*8); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_MIN_LEN, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_CRC); -} - -/** - * @brief Encode a actuator_control_target struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param actuator_control_target C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_actuator_control_target_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_actuator_control_target_t* actuator_control_target) -{ - return mavlink_msg_actuator_control_target_pack(system_id, component_id, msg, actuator_control_target->time_usec, actuator_control_target->group_mlx, actuator_control_target->controls); -} - -/** - * @brief Encode a actuator_control_target struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param actuator_control_target C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_actuator_control_target_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_actuator_control_target_t* actuator_control_target) -{ - return mavlink_msg_actuator_control_target_pack_chan(system_id, component_id, chan, msg, actuator_control_target->time_usec, actuator_control_target->group_mlx, actuator_control_target->controls); -} - -/** - * @brief Send a actuator_control_target message - * @param chan MAVLink channel to send the message - * - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @param group_mlx Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances. - * @param controls Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_actuator_control_target_send(mavlink_channel_t chan, uint64_t time_usec, uint8_t group_mlx, const float *controls) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint8_t(buf, 40, group_mlx); - _mav_put_float_array(buf, 8, controls, 8); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET, buf, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_MIN_LEN, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_CRC); -#else - mavlink_actuator_control_target_t packet; - packet.time_usec = time_usec; - packet.group_mlx = group_mlx; - mav_array_memcpy(packet.controls, controls, sizeof(float)*8); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET, (const char *)&packet, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_MIN_LEN, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_CRC); -#endif -} - -/** - * @brief Send a actuator_control_target message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_actuator_control_target_send_struct(mavlink_channel_t chan, const mavlink_actuator_control_target_t* actuator_control_target) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_actuator_control_target_send(chan, actuator_control_target->time_usec, actuator_control_target->group_mlx, actuator_control_target->controls); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET, (const char *)actuator_control_target, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_MIN_LEN, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_CRC); -#endif -} - -#if MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_actuator_control_target_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, uint8_t group_mlx, const float *controls) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint8_t(buf, 40, group_mlx); - _mav_put_float_array(buf, 8, controls, 8); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET, buf, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_MIN_LEN, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_CRC); -#else - mavlink_actuator_control_target_t *packet = (mavlink_actuator_control_target_t *)msgbuf; - packet->time_usec = time_usec; - packet->group_mlx = group_mlx; - mav_array_memcpy(packet->controls, controls, sizeof(float)*8); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET, (const char *)packet, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_MIN_LEN, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_CRC); -#endif -} -#endif - -#endif - -// MESSAGE ACTUATOR_CONTROL_TARGET UNPACKING - - -/** - * @brief Get field time_usec from actuator_control_target message - * - * @return [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - */ -static inline uint64_t mavlink_msg_actuator_control_target_get_time_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field group_mlx from actuator_control_target message - * - * @return Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances. - */ -static inline uint8_t mavlink_msg_actuator_control_target_get_group_mlx(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 40); -} - -/** - * @brief Get field controls from actuator_control_target message - * - * @return Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs. - */ -static inline uint16_t mavlink_msg_actuator_control_target_get_controls(const mavlink_message_t* msg, float *controls) -{ - return _MAV_RETURN_float_array(msg, controls, 8, 8); -} - -/** - * @brief Decode a actuator_control_target message into a struct - * - * @param msg The message to decode - * @param actuator_control_target C-struct to decode the message contents into - */ -static inline void mavlink_msg_actuator_control_target_decode(const mavlink_message_t* msg, mavlink_actuator_control_target_t* actuator_control_target) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - actuator_control_target->time_usec = mavlink_msg_actuator_control_target_get_time_usec(msg); - mavlink_msg_actuator_control_target_get_controls(msg, actuator_control_target->controls); - actuator_control_target->group_mlx = mavlink_msg_actuator_control_target_get_group_mlx(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN? msg->len : MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN; - memset(actuator_control_target, 0, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN); - memcpy(actuator_control_target, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_actuator_output_status.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_actuator_output_status.h deleted file mode 100644 index 4fc1069b..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_actuator_output_status.h +++ /dev/null @@ -1,255 +0,0 @@ -#pragma once -// MESSAGE ACTUATOR_OUTPUT_STATUS PACKING - -#define MAVLINK_MSG_ID_ACTUATOR_OUTPUT_STATUS 375 - - -typedef struct __mavlink_actuator_output_status_t { - uint64_t time_usec; /*< [us] Timestamp (since system boot).*/ - uint32_t active; /*< Active outputs*/ - float actuator[32]; /*< Servo / motor output array values. Zero values indicate unused channels.*/ -} mavlink_actuator_output_status_t; - -#define MAVLINK_MSG_ID_ACTUATOR_OUTPUT_STATUS_LEN 140 -#define MAVLINK_MSG_ID_ACTUATOR_OUTPUT_STATUS_MIN_LEN 140 -#define MAVLINK_MSG_ID_375_LEN 140 -#define MAVLINK_MSG_ID_375_MIN_LEN 140 - -#define MAVLINK_MSG_ID_ACTUATOR_OUTPUT_STATUS_CRC 251 -#define MAVLINK_MSG_ID_375_CRC 251 - -#define MAVLINK_MSG_ACTUATOR_OUTPUT_STATUS_FIELD_ACTUATOR_LEN 32 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_ACTUATOR_OUTPUT_STATUS { \ - 375, \ - "ACTUATOR_OUTPUT_STATUS", \ - 3, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_actuator_output_status_t, time_usec) }, \ - { "active", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_actuator_output_status_t, active) }, \ - { "actuator", NULL, MAVLINK_TYPE_FLOAT, 32, 12, offsetof(mavlink_actuator_output_status_t, actuator) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_ACTUATOR_OUTPUT_STATUS { \ - "ACTUATOR_OUTPUT_STATUS", \ - 3, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_actuator_output_status_t, time_usec) }, \ - { "active", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_actuator_output_status_t, active) }, \ - { "actuator", NULL, MAVLINK_TYPE_FLOAT, 32, 12, offsetof(mavlink_actuator_output_status_t, actuator) }, \ - } \ -} -#endif - -/** - * @brief Pack a actuator_output_status message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param time_usec [us] Timestamp (since system boot). - * @param active Active outputs - * @param actuator Servo / motor output array values. Zero values indicate unused channels. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_actuator_output_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint64_t time_usec, uint32_t active, const float *actuator) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_ACTUATOR_OUTPUT_STATUS_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint32_t(buf, 8, active); - _mav_put_float_array(buf, 12, actuator, 32); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ACTUATOR_OUTPUT_STATUS_LEN); -#else - mavlink_actuator_output_status_t packet; - packet.time_usec = time_usec; - packet.active = active; - mav_array_memcpy(packet.actuator, actuator, sizeof(float)*32); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ACTUATOR_OUTPUT_STATUS_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_ACTUATOR_OUTPUT_STATUS; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ACTUATOR_OUTPUT_STATUS_MIN_LEN, MAVLINK_MSG_ID_ACTUATOR_OUTPUT_STATUS_LEN, MAVLINK_MSG_ID_ACTUATOR_OUTPUT_STATUS_CRC); -} - -/** - * @brief Pack a actuator_output_status message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_usec [us] Timestamp (since system boot). - * @param active Active outputs - * @param actuator Servo / motor output array values. Zero values indicate unused channels. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_actuator_output_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint64_t time_usec,uint32_t active,const float *actuator) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_ACTUATOR_OUTPUT_STATUS_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint32_t(buf, 8, active); - _mav_put_float_array(buf, 12, actuator, 32); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ACTUATOR_OUTPUT_STATUS_LEN); -#else - mavlink_actuator_output_status_t packet; - packet.time_usec = time_usec; - packet.active = active; - mav_array_memcpy(packet.actuator, actuator, sizeof(float)*32); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ACTUATOR_OUTPUT_STATUS_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_ACTUATOR_OUTPUT_STATUS; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ACTUATOR_OUTPUT_STATUS_MIN_LEN, MAVLINK_MSG_ID_ACTUATOR_OUTPUT_STATUS_LEN, MAVLINK_MSG_ID_ACTUATOR_OUTPUT_STATUS_CRC); -} - -/** - * @brief Encode a actuator_output_status struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param actuator_output_status C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_actuator_output_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_actuator_output_status_t* actuator_output_status) -{ - return mavlink_msg_actuator_output_status_pack(system_id, component_id, msg, actuator_output_status->time_usec, actuator_output_status->active, actuator_output_status->actuator); -} - -/** - * @brief Encode a actuator_output_status struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param actuator_output_status C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_actuator_output_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_actuator_output_status_t* actuator_output_status) -{ - return mavlink_msg_actuator_output_status_pack_chan(system_id, component_id, chan, msg, actuator_output_status->time_usec, actuator_output_status->active, actuator_output_status->actuator); -} - -/** - * @brief Send a actuator_output_status message - * @param chan MAVLink channel to send the message - * - * @param time_usec [us] Timestamp (since system boot). - * @param active Active outputs - * @param actuator Servo / motor output array values. Zero values indicate unused channels. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_actuator_output_status_send(mavlink_channel_t chan, uint64_t time_usec, uint32_t active, const float *actuator) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_ACTUATOR_OUTPUT_STATUS_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint32_t(buf, 8, active); - _mav_put_float_array(buf, 12, actuator, 32); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ACTUATOR_OUTPUT_STATUS, buf, MAVLINK_MSG_ID_ACTUATOR_OUTPUT_STATUS_MIN_LEN, MAVLINK_MSG_ID_ACTUATOR_OUTPUT_STATUS_LEN, MAVLINK_MSG_ID_ACTUATOR_OUTPUT_STATUS_CRC); -#else - mavlink_actuator_output_status_t packet; - packet.time_usec = time_usec; - packet.active = active; - mav_array_memcpy(packet.actuator, actuator, sizeof(float)*32); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ACTUATOR_OUTPUT_STATUS, (const char *)&packet, MAVLINK_MSG_ID_ACTUATOR_OUTPUT_STATUS_MIN_LEN, MAVLINK_MSG_ID_ACTUATOR_OUTPUT_STATUS_LEN, MAVLINK_MSG_ID_ACTUATOR_OUTPUT_STATUS_CRC); -#endif -} - -/** - * @brief Send a actuator_output_status message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_actuator_output_status_send_struct(mavlink_channel_t chan, const mavlink_actuator_output_status_t* actuator_output_status) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_actuator_output_status_send(chan, actuator_output_status->time_usec, actuator_output_status->active, actuator_output_status->actuator); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ACTUATOR_OUTPUT_STATUS, (const char *)actuator_output_status, MAVLINK_MSG_ID_ACTUATOR_OUTPUT_STATUS_MIN_LEN, MAVLINK_MSG_ID_ACTUATOR_OUTPUT_STATUS_LEN, MAVLINK_MSG_ID_ACTUATOR_OUTPUT_STATUS_CRC); -#endif -} - -#if MAVLINK_MSG_ID_ACTUATOR_OUTPUT_STATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_actuator_output_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, uint32_t active, const float *actuator) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint32_t(buf, 8, active); - _mav_put_float_array(buf, 12, actuator, 32); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ACTUATOR_OUTPUT_STATUS, buf, MAVLINK_MSG_ID_ACTUATOR_OUTPUT_STATUS_MIN_LEN, MAVLINK_MSG_ID_ACTUATOR_OUTPUT_STATUS_LEN, MAVLINK_MSG_ID_ACTUATOR_OUTPUT_STATUS_CRC); -#else - mavlink_actuator_output_status_t *packet = (mavlink_actuator_output_status_t *)msgbuf; - packet->time_usec = time_usec; - packet->active = active; - mav_array_memcpy(packet->actuator, actuator, sizeof(float)*32); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ACTUATOR_OUTPUT_STATUS, (const char *)packet, MAVLINK_MSG_ID_ACTUATOR_OUTPUT_STATUS_MIN_LEN, MAVLINK_MSG_ID_ACTUATOR_OUTPUT_STATUS_LEN, MAVLINK_MSG_ID_ACTUATOR_OUTPUT_STATUS_CRC); -#endif -} -#endif - -#endif - -// MESSAGE ACTUATOR_OUTPUT_STATUS UNPACKING - - -/** - * @brief Get field time_usec from actuator_output_status message - * - * @return [us] Timestamp (since system boot). - */ -static inline uint64_t mavlink_msg_actuator_output_status_get_time_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field active from actuator_output_status message - * - * @return Active outputs - */ -static inline uint32_t mavlink_msg_actuator_output_status_get_active(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 8); -} - -/** - * @brief Get field actuator from actuator_output_status message - * - * @return Servo / motor output array values. Zero values indicate unused channels. - */ -static inline uint16_t mavlink_msg_actuator_output_status_get_actuator(const mavlink_message_t* msg, float *actuator) -{ - return _MAV_RETURN_float_array(msg, actuator, 32, 12); -} - -/** - * @brief Decode a actuator_output_status message into a struct - * - * @param msg The message to decode - * @param actuator_output_status C-struct to decode the message contents into - */ -static inline void mavlink_msg_actuator_output_status_decode(const mavlink_message_t* msg, mavlink_actuator_output_status_t* actuator_output_status) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - actuator_output_status->time_usec = mavlink_msg_actuator_output_status_get_time_usec(msg); - actuator_output_status->active = mavlink_msg_actuator_output_status_get_active(msg); - mavlink_msg_actuator_output_status_get_actuator(msg, actuator_output_status->actuator); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_ACTUATOR_OUTPUT_STATUS_LEN? msg->len : MAVLINK_MSG_ID_ACTUATOR_OUTPUT_STATUS_LEN; - memset(actuator_output_status, 0, MAVLINK_MSG_ID_ACTUATOR_OUTPUT_STATUS_LEN); - memcpy(actuator_output_status, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_adsb_vehicle.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_adsb_vehicle.h deleted file mode 100644 index d6220289..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_adsb_vehicle.h +++ /dev/null @@ -1,505 +0,0 @@ -#pragma once -// MESSAGE ADSB_VEHICLE PACKING - -#define MAVLINK_MSG_ID_ADSB_VEHICLE 246 - - -typedef struct __mavlink_adsb_vehicle_t { - uint32_t ICAO_address; /*< ICAO address*/ - int32_t lat; /*< [degE7] Latitude*/ - int32_t lon; /*< [degE7] Longitude*/ - int32_t altitude; /*< [mm] Altitude(ASL)*/ - uint16_t heading; /*< [cdeg] Course over ground*/ - uint16_t hor_velocity; /*< [cm/s] The horizontal velocity*/ - int16_t ver_velocity; /*< [cm/s] The vertical velocity. Positive is up*/ - uint16_t flags; /*< Bitmap to indicate various statuses including valid data fields*/ - uint16_t squawk; /*< Squawk code*/ - uint8_t altitude_type; /*< ADSB altitude type.*/ - char callsign[9]; /*< The callsign, 8+null*/ - uint8_t emitter_type; /*< ADSB emitter type.*/ - uint8_t tslc; /*< [s] Time since last communication in seconds*/ -} mavlink_adsb_vehicle_t; - -#define MAVLINK_MSG_ID_ADSB_VEHICLE_LEN 38 -#define MAVLINK_MSG_ID_ADSB_VEHICLE_MIN_LEN 38 -#define MAVLINK_MSG_ID_246_LEN 38 -#define MAVLINK_MSG_ID_246_MIN_LEN 38 - -#define MAVLINK_MSG_ID_ADSB_VEHICLE_CRC 184 -#define MAVLINK_MSG_ID_246_CRC 184 - -#define MAVLINK_MSG_ADSB_VEHICLE_FIELD_CALLSIGN_LEN 9 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_ADSB_VEHICLE { \ - 246, \ - "ADSB_VEHICLE", \ - 13, \ - { { "ICAO_address", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_adsb_vehicle_t, ICAO_address) }, \ - { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_adsb_vehicle_t, lat) }, \ - { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_adsb_vehicle_t, lon) }, \ - { "altitude_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 26, offsetof(mavlink_adsb_vehicle_t, altitude_type) }, \ - { "altitude", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_adsb_vehicle_t, altitude) }, \ - { "heading", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_adsb_vehicle_t, heading) }, \ - { "hor_velocity", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_adsb_vehicle_t, hor_velocity) }, \ - { "ver_velocity", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_adsb_vehicle_t, ver_velocity) }, \ - { "callsign", NULL, MAVLINK_TYPE_CHAR, 9, 27, offsetof(mavlink_adsb_vehicle_t, callsign) }, \ - { "emitter_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_adsb_vehicle_t, emitter_type) }, \ - { "tslc", NULL, MAVLINK_TYPE_UINT8_T, 0, 37, offsetof(mavlink_adsb_vehicle_t, tslc) }, \ - { "flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_adsb_vehicle_t, flags) }, \ - { "squawk", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_adsb_vehicle_t, squawk) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_ADSB_VEHICLE { \ - "ADSB_VEHICLE", \ - 13, \ - { { "ICAO_address", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_adsb_vehicle_t, ICAO_address) }, \ - { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_adsb_vehicle_t, lat) }, \ - { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_adsb_vehicle_t, lon) }, \ - { "altitude_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 26, offsetof(mavlink_adsb_vehicle_t, altitude_type) }, \ - { "altitude", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_adsb_vehicle_t, altitude) }, \ - { "heading", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_adsb_vehicle_t, heading) }, \ - { "hor_velocity", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_adsb_vehicle_t, hor_velocity) }, \ - { "ver_velocity", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_adsb_vehicle_t, ver_velocity) }, \ - { "callsign", NULL, MAVLINK_TYPE_CHAR, 9, 27, offsetof(mavlink_adsb_vehicle_t, callsign) }, \ - { "emitter_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_adsb_vehicle_t, emitter_type) }, \ - { "tslc", NULL, MAVLINK_TYPE_UINT8_T, 0, 37, offsetof(mavlink_adsb_vehicle_t, tslc) }, \ - { "flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_adsb_vehicle_t, flags) }, \ - { "squawk", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_adsb_vehicle_t, squawk) }, \ - } \ -} -#endif - -/** - * @brief Pack a adsb_vehicle message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param ICAO_address ICAO address - * @param lat [degE7] Latitude - * @param lon [degE7] Longitude - * @param altitude_type ADSB altitude type. - * @param altitude [mm] Altitude(ASL) - * @param heading [cdeg] Course over ground - * @param hor_velocity [cm/s] The horizontal velocity - * @param ver_velocity [cm/s] The vertical velocity. Positive is up - * @param callsign The callsign, 8+null - * @param emitter_type ADSB emitter type. - * @param tslc [s] Time since last communication in seconds - * @param flags Bitmap to indicate various statuses including valid data fields - * @param squawk Squawk code - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_adsb_vehicle_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint32_t ICAO_address, int32_t lat, int32_t lon, uint8_t altitude_type, int32_t altitude, uint16_t heading, uint16_t hor_velocity, int16_t ver_velocity, const char *callsign, uint8_t emitter_type, uint8_t tslc, uint16_t flags, uint16_t squawk) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_ADSB_VEHICLE_LEN]; - _mav_put_uint32_t(buf, 0, ICAO_address); - _mav_put_int32_t(buf, 4, lat); - _mav_put_int32_t(buf, 8, lon); - _mav_put_int32_t(buf, 12, altitude); - _mav_put_uint16_t(buf, 16, heading); - _mav_put_uint16_t(buf, 18, hor_velocity); - _mav_put_int16_t(buf, 20, ver_velocity); - _mav_put_uint16_t(buf, 22, flags); - _mav_put_uint16_t(buf, 24, squawk); - _mav_put_uint8_t(buf, 26, altitude_type); - _mav_put_uint8_t(buf, 36, emitter_type); - _mav_put_uint8_t(buf, 37, tslc); - _mav_put_char_array(buf, 27, callsign, 9); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ADSB_VEHICLE_LEN); -#else - mavlink_adsb_vehicle_t packet; - packet.ICAO_address = ICAO_address; - packet.lat = lat; - packet.lon = lon; - packet.altitude = altitude; - packet.heading = heading; - packet.hor_velocity = hor_velocity; - packet.ver_velocity = ver_velocity; - packet.flags = flags; - packet.squawk = squawk; - packet.altitude_type = altitude_type; - packet.emitter_type = emitter_type; - packet.tslc = tslc; - mav_array_memcpy(packet.callsign, callsign, sizeof(char)*9); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ADSB_VEHICLE_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_ADSB_VEHICLE; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ADSB_VEHICLE_MIN_LEN, MAVLINK_MSG_ID_ADSB_VEHICLE_LEN, MAVLINK_MSG_ID_ADSB_VEHICLE_CRC); -} - -/** - * @brief Pack a adsb_vehicle message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param ICAO_address ICAO address - * @param lat [degE7] Latitude - * @param lon [degE7] Longitude - * @param altitude_type ADSB altitude type. - * @param altitude [mm] Altitude(ASL) - * @param heading [cdeg] Course over ground - * @param hor_velocity [cm/s] The horizontal velocity - * @param ver_velocity [cm/s] The vertical velocity. Positive is up - * @param callsign The callsign, 8+null - * @param emitter_type ADSB emitter type. - * @param tslc [s] Time since last communication in seconds - * @param flags Bitmap to indicate various statuses including valid data fields - * @param squawk Squawk code - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_adsb_vehicle_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint32_t ICAO_address,int32_t lat,int32_t lon,uint8_t altitude_type,int32_t altitude,uint16_t heading,uint16_t hor_velocity,int16_t ver_velocity,const char *callsign,uint8_t emitter_type,uint8_t tslc,uint16_t flags,uint16_t squawk) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_ADSB_VEHICLE_LEN]; - _mav_put_uint32_t(buf, 0, ICAO_address); - _mav_put_int32_t(buf, 4, lat); - _mav_put_int32_t(buf, 8, lon); - _mav_put_int32_t(buf, 12, altitude); - _mav_put_uint16_t(buf, 16, heading); - _mav_put_uint16_t(buf, 18, hor_velocity); - _mav_put_int16_t(buf, 20, ver_velocity); - _mav_put_uint16_t(buf, 22, flags); - _mav_put_uint16_t(buf, 24, squawk); - _mav_put_uint8_t(buf, 26, altitude_type); - _mav_put_uint8_t(buf, 36, emitter_type); - _mav_put_uint8_t(buf, 37, tslc); - _mav_put_char_array(buf, 27, callsign, 9); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ADSB_VEHICLE_LEN); -#else - mavlink_adsb_vehicle_t packet; - packet.ICAO_address = ICAO_address; - packet.lat = lat; - packet.lon = lon; - packet.altitude = altitude; - packet.heading = heading; - packet.hor_velocity = hor_velocity; - packet.ver_velocity = ver_velocity; - packet.flags = flags; - packet.squawk = squawk; - packet.altitude_type = altitude_type; - packet.emitter_type = emitter_type; - packet.tslc = tslc; - mav_array_memcpy(packet.callsign, callsign, sizeof(char)*9); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ADSB_VEHICLE_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_ADSB_VEHICLE; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ADSB_VEHICLE_MIN_LEN, MAVLINK_MSG_ID_ADSB_VEHICLE_LEN, MAVLINK_MSG_ID_ADSB_VEHICLE_CRC); -} - -/** - * @brief Encode a adsb_vehicle struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param adsb_vehicle C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_adsb_vehicle_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_adsb_vehicle_t* adsb_vehicle) -{ - return mavlink_msg_adsb_vehicle_pack(system_id, component_id, msg, adsb_vehicle->ICAO_address, adsb_vehicle->lat, adsb_vehicle->lon, adsb_vehicle->altitude_type, adsb_vehicle->altitude, adsb_vehicle->heading, adsb_vehicle->hor_velocity, adsb_vehicle->ver_velocity, adsb_vehicle->callsign, adsb_vehicle->emitter_type, adsb_vehicle->tslc, adsb_vehicle->flags, adsb_vehicle->squawk); -} - -/** - * @brief Encode a adsb_vehicle struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param adsb_vehicle C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_adsb_vehicle_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_adsb_vehicle_t* adsb_vehicle) -{ - return mavlink_msg_adsb_vehicle_pack_chan(system_id, component_id, chan, msg, adsb_vehicle->ICAO_address, adsb_vehicle->lat, adsb_vehicle->lon, adsb_vehicle->altitude_type, adsb_vehicle->altitude, adsb_vehicle->heading, adsb_vehicle->hor_velocity, adsb_vehicle->ver_velocity, adsb_vehicle->callsign, adsb_vehicle->emitter_type, adsb_vehicle->tslc, adsb_vehicle->flags, adsb_vehicle->squawk); -} - -/** - * @brief Send a adsb_vehicle message - * @param chan MAVLink channel to send the message - * - * @param ICAO_address ICAO address - * @param lat [degE7] Latitude - * @param lon [degE7] Longitude - * @param altitude_type ADSB altitude type. - * @param altitude [mm] Altitude(ASL) - * @param heading [cdeg] Course over ground - * @param hor_velocity [cm/s] The horizontal velocity - * @param ver_velocity [cm/s] The vertical velocity. Positive is up - * @param callsign The callsign, 8+null - * @param emitter_type ADSB emitter type. - * @param tslc [s] Time since last communication in seconds - * @param flags Bitmap to indicate various statuses including valid data fields - * @param squawk Squawk code - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_adsb_vehicle_send(mavlink_channel_t chan, uint32_t ICAO_address, int32_t lat, int32_t lon, uint8_t altitude_type, int32_t altitude, uint16_t heading, uint16_t hor_velocity, int16_t ver_velocity, const char *callsign, uint8_t emitter_type, uint8_t tslc, uint16_t flags, uint16_t squawk) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_ADSB_VEHICLE_LEN]; - _mav_put_uint32_t(buf, 0, ICAO_address); - _mav_put_int32_t(buf, 4, lat); - _mav_put_int32_t(buf, 8, lon); - _mav_put_int32_t(buf, 12, altitude); - _mav_put_uint16_t(buf, 16, heading); - _mav_put_uint16_t(buf, 18, hor_velocity); - _mav_put_int16_t(buf, 20, ver_velocity); - _mav_put_uint16_t(buf, 22, flags); - _mav_put_uint16_t(buf, 24, squawk); - _mav_put_uint8_t(buf, 26, altitude_type); - _mav_put_uint8_t(buf, 36, emitter_type); - _mav_put_uint8_t(buf, 37, tslc); - _mav_put_char_array(buf, 27, callsign, 9); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ADSB_VEHICLE, buf, MAVLINK_MSG_ID_ADSB_VEHICLE_MIN_LEN, MAVLINK_MSG_ID_ADSB_VEHICLE_LEN, MAVLINK_MSG_ID_ADSB_VEHICLE_CRC); -#else - mavlink_adsb_vehicle_t packet; - packet.ICAO_address = ICAO_address; - packet.lat = lat; - packet.lon = lon; - packet.altitude = altitude; - packet.heading = heading; - packet.hor_velocity = hor_velocity; - packet.ver_velocity = ver_velocity; - packet.flags = flags; - packet.squawk = squawk; - packet.altitude_type = altitude_type; - packet.emitter_type = emitter_type; - packet.tslc = tslc; - mav_array_memcpy(packet.callsign, callsign, sizeof(char)*9); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ADSB_VEHICLE, (const char *)&packet, MAVLINK_MSG_ID_ADSB_VEHICLE_MIN_LEN, MAVLINK_MSG_ID_ADSB_VEHICLE_LEN, MAVLINK_MSG_ID_ADSB_VEHICLE_CRC); -#endif -} - -/** - * @brief Send a adsb_vehicle message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_adsb_vehicle_send_struct(mavlink_channel_t chan, const mavlink_adsb_vehicle_t* adsb_vehicle) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_adsb_vehicle_send(chan, adsb_vehicle->ICAO_address, adsb_vehicle->lat, adsb_vehicle->lon, adsb_vehicle->altitude_type, adsb_vehicle->altitude, adsb_vehicle->heading, adsb_vehicle->hor_velocity, adsb_vehicle->ver_velocity, adsb_vehicle->callsign, adsb_vehicle->emitter_type, adsb_vehicle->tslc, adsb_vehicle->flags, adsb_vehicle->squawk); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ADSB_VEHICLE, (const char *)adsb_vehicle, MAVLINK_MSG_ID_ADSB_VEHICLE_MIN_LEN, MAVLINK_MSG_ID_ADSB_VEHICLE_LEN, MAVLINK_MSG_ID_ADSB_VEHICLE_CRC); -#endif -} - -#if MAVLINK_MSG_ID_ADSB_VEHICLE_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_adsb_vehicle_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t ICAO_address, int32_t lat, int32_t lon, uint8_t altitude_type, int32_t altitude, uint16_t heading, uint16_t hor_velocity, int16_t ver_velocity, const char *callsign, uint8_t emitter_type, uint8_t tslc, uint16_t flags, uint16_t squawk) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, ICAO_address); - _mav_put_int32_t(buf, 4, lat); - _mav_put_int32_t(buf, 8, lon); - _mav_put_int32_t(buf, 12, altitude); - _mav_put_uint16_t(buf, 16, heading); - _mav_put_uint16_t(buf, 18, hor_velocity); - _mav_put_int16_t(buf, 20, ver_velocity); - _mav_put_uint16_t(buf, 22, flags); - _mav_put_uint16_t(buf, 24, squawk); - _mav_put_uint8_t(buf, 26, altitude_type); - _mav_put_uint8_t(buf, 36, emitter_type); - _mav_put_uint8_t(buf, 37, tslc); - _mav_put_char_array(buf, 27, callsign, 9); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ADSB_VEHICLE, buf, MAVLINK_MSG_ID_ADSB_VEHICLE_MIN_LEN, MAVLINK_MSG_ID_ADSB_VEHICLE_LEN, MAVLINK_MSG_ID_ADSB_VEHICLE_CRC); -#else - mavlink_adsb_vehicle_t *packet = (mavlink_adsb_vehicle_t *)msgbuf; - packet->ICAO_address = ICAO_address; - packet->lat = lat; - packet->lon = lon; - packet->altitude = altitude; - packet->heading = heading; - packet->hor_velocity = hor_velocity; - packet->ver_velocity = ver_velocity; - packet->flags = flags; - packet->squawk = squawk; - packet->altitude_type = altitude_type; - packet->emitter_type = emitter_type; - packet->tslc = tslc; - mav_array_memcpy(packet->callsign, callsign, sizeof(char)*9); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ADSB_VEHICLE, (const char *)packet, MAVLINK_MSG_ID_ADSB_VEHICLE_MIN_LEN, MAVLINK_MSG_ID_ADSB_VEHICLE_LEN, MAVLINK_MSG_ID_ADSB_VEHICLE_CRC); -#endif -} -#endif - -#endif - -// MESSAGE ADSB_VEHICLE UNPACKING - - -/** - * @brief Get field ICAO_address from adsb_vehicle message - * - * @return ICAO address - */ -static inline uint32_t mavlink_msg_adsb_vehicle_get_ICAO_address(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field lat from adsb_vehicle message - * - * @return [degE7] Latitude - */ -static inline int32_t mavlink_msg_adsb_vehicle_get_lat(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 4); -} - -/** - * @brief Get field lon from adsb_vehicle message - * - * @return [degE7] Longitude - */ -static inline int32_t mavlink_msg_adsb_vehicle_get_lon(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 8); -} - -/** - * @brief Get field altitude_type from adsb_vehicle message - * - * @return ADSB altitude type. - */ -static inline uint8_t mavlink_msg_adsb_vehicle_get_altitude_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 26); -} - -/** - * @brief Get field altitude from adsb_vehicle message - * - * @return [mm] Altitude(ASL) - */ -static inline int32_t mavlink_msg_adsb_vehicle_get_altitude(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 12); -} - -/** - * @brief Get field heading from adsb_vehicle message - * - * @return [cdeg] Course over ground - */ -static inline uint16_t mavlink_msg_adsb_vehicle_get_heading(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 16); -} - -/** - * @brief Get field hor_velocity from adsb_vehicle message - * - * @return [cm/s] The horizontal velocity - */ -static inline uint16_t mavlink_msg_adsb_vehicle_get_hor_velocity(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 18); -} - -/** - * @brief Get field ver_velocity from adsb_vehicle message - * - * @return [cm/s] The vertical velocity. Positive is up - */ -static inline int16_t mavlink_msg_adsb_vehicle_get_ver_velocity(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 20); -} - -/** - * @brief Get field callsign from adsb_vehicle message - * - * @return The callsign, 8+null - */ -static inline uint16_t mavlink_msg_adsb_vehicle_get_callsign(const mavlink_message_t* msg, char *callsign) -{ - return _MAV_RETURN_char_array(msg, callsign, 9, 27); -} - -/** - * @brief Get field emitter_type from adsb_vehicle message - * - * @return ADSB emitter type. - */ -static inline uint8_t mavlink_msg_adsb_vehicle_get_emitter_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 36); -} - -/** - * @brief Get field tslc from adsb_vehicle message - * - * @return [s] Time since last communication in seconds - */ -static inline uint8_t mavlink_msg_adsb_vehicle_get_tslc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 37); -} - -/** - * @brief Get field flags from adsb_vehicle message - * - * @return Bitmap to indicate various statuses including valid data fields - */ -static inline uint16_t mavlink_msg_adsb_vehicle_get_flags(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 22); -} - -/** - * @brief Get field squawk from adsb_vehicle message - * - * @return Squawk code - */ -static inline uint16_t mavlink_msg_adsb_vehicle_get_squawk(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 24); -} - -/** - * @brief Decode a adsb_vehicle message into a struct - * - * @param msg The message to decode - * @param adsb_vehicle C-struct to decode the message contents into - */ -static inline void mavlink_msg_adsb_vehicle_decode(const mavlink_message_t* msg, mavlink_adsb_vehicle_t* adsb_vehicle) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - adsb_vehicle->ICAO_address = mavlink_msg_adsb_vehicle_get_ICAO_address(msg); - adsb_vehicle->lat = mavlink_msg_adsb_vehicle_get_lat(msg); - adsb_vehicle->lon = mavlink_msg_adsb_vehicle_get_lon(msg); - adsb_vehicle->altitude = mavlink_msg_adsb_vehicle_get_altitude(msg); - adsb_vehicle->heading = mavlink_msg_adsb_vehicle_get_heading(msg); - adsb_vehicle->hor_velocity = mavlink_msg_adsb_vehicle_get_hor_velocity(msg); - adsb_vehicle->ver_velocity = mavlink_msg_adsb_vehicle_get_ver_velocity(msg); - adsb_vehicle->flags = mavlink_msg_adsb_vehicle_get_flags(msg); - adsb_vehicle->squawk = mavlink_msg_adsb_vehicle_get_squawk(msg); - adsb_vehicle->altitude_type = mavlink_msg_adsb_vehicle_get_altitude_type(msg); - mavlink_msg_adsb_vehicle_get_callsign(msg, adsb_vehicle->callsign); - adsb_vehicle->emitter_type = mavlink_msg_adsb_vehicle_get_emitter_type(msg); - adsb_vehicle->tslc = mavlink_msg_adsb_vehicle_get_tslc(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_ADSB_VEHICLE_LEN? msg->len : MAVLINK_MSG_ID_ADSB_VEHICLE_LEN; - memset(adsb_vehicle, 0, MAVLINK_MSG_ID_ADSB_VEHICLE_LEN); - memcpy(adsb_vehicle, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_ais_vessel.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_ais_vessel.h deleted file mode 100644 index 1e1287b7..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_ais_vessel.h +++ /dev/null @@ -1,606 +0,0 @@ -#pragma once -// MESSAGE AIS_VESSEL PACKING - -#define MAVLINK_MSG_ID_AIS_VESSEL 301 - - -typedef struct __mavlink_ais_vessel_t { - uint32_t MMSI; /*< Mobile Marine Service Identifier, 9 decimal digits*/ - int32_t lat; /*< [degE7] Latitude*/ - int32_t lon; /*< [degE7] Longitude*/ - uint16_t COG; /*< [cdeg] Course over ground*/ - uint16_t heading; /*< [cdeg] True heading*/ - uint16_t velocity; /*< [cm/s] Speed over ground*/ - uint16_t dimension_bow; /*< [m] Distance from lat/lon location to bow*/ - uint16_t dimension_stern; /*< [m] Distance from lat/lon location to stern*/ - uint16_t tslc; /*< [s] Time since last communication in seconds*/ - uint16_t flags; /*< Bitmask to indicate various statuses including valid data fields*/ - int8_t turn_rate; /*< [cdeg/s] Turn rate*/ - uint8_t navigational_status; /*< Navigational status*/ - uint8_t type; /*< Type of vessels*/ - uint8_t dimension_port; /*< [m] Distance from lat/lon location to port side*/ - uint8_t dimension_starboard; /*< [m] Distance from lat/lon location to starboard side*/ - char callsign[7]; /*< The vessel callsign*/ - char name[20]; /*< The vessel name*/ -} mavlink_ais_vessel_t; - -#define MAVLINK_MSG_ID_AIS_VESSEL_LEN 58 -#define MAVLINK_MSG_ID_AIS_VESSEL_MIN_LEN 58 -#define MAVLINK_MSG_ID_301_LEN 58 -#define MAVLINK_MSG_ID_301_MIN_LEN 58 - -#define MAVLINK_MSG_ID_AIS_VESSEL_CRC 243 -#define MAVLINK_MSG_ID_301_CRC 243 - -#define MAVLINK_MSG_AIS_VESSEL_FIELD_CALLSIGN_LEN 7 -#define MAVLINK_MSG_AIS_VESSEL_FIELD_NAME_LEN 20 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_AIS_VESSEL { \ - 301, \ - "AIS_VESSEL", \ - 17, \ - { { "MMSI", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_ais_vessel_t, MMSI) }, \ - { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_ais_vessel_t, lat) }, \ - { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_ais_vessel_t, lon) }, \ - { "COG", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_ais_vessel_t, COG) }, \ - { "heading", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_ais_vessel_t, heading) }, \ - { "velocity", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_ais_vessel_t, velocity) }, \ - { "turn_rate", NULL, MAVLINK_TYPE_INT8_T, 0, 26, offsetof(mavlink_ais_vessel_t, turn_rate) }, \ - { "navigational_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 27, offsetof(mavlink_ais_vessel_t, navigational_status) }, \ - { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 28, offsetof(mavlink_ais_vessel_t, type) }, \ - { "dimension_bow", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_ais_vessel_t, dimension_bow) }, \ - { "dimension_stern", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_ais_vessel_t, dimension_stern) }, \ - { "dimension_port", NULL, MAVLINK_TYPE_UINT8_T, 0, 29, offsetof(mavlink_ais_vessel_t, dimension_port) }, \ - { "dimension_starboard", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_ais_vessel_t, dimension_starboard) }, \ - { "callsign", NULL, MAVLINK_TYPE_CHAR, 7, 31, offsetof(mavlink_ais_vessel_t, callsign) }, \ - { "name", NULL, MAVLINK_TYPE_CHAR, 20, 38, offsetof(mavlink_ais_vessel_t, name) }, \ - { "tslc", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_ais_vessel_t, tslc) }, \ - { "flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_ais_vessel_t, flags) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_AIS_VESSEL { \ - "AIS_VESSEL", \ - 17, \ - { { "MMSI", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_ais_vessel_t, MMSI) }, \ - { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_ais_vessel_t, lat) }, \ - { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_ais_vessel_t, lon) }, \ - { "COG", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_ais_vessel_t, COG) }, \ - { "heading", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_ais_vessel_t, heading) }, \ - { "velocity", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_ais_vessel_t, velocity) }, \ - { "turn_rate", NULL, MAVLINK_TYPE_INT8_T, 0, 26, offsetof(mavlink_ais_vessel_t, turn_rate) }, \ - { "navigational_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 27, offsetof(mavlink_ais_vessel_t, navigational_status) }, \ - { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 28, offsetof(mavlink_ais_vessel_t, type) }, \ - { "dimension_bow", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_ais_vessel_t, dimension_bow) }, \ - { "dimension_stern", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_ais_vessel_t, dimension_stern) }, \ - { "dimension_port", NULL, MAVLINK_TYPE_UINT8_T, 0, 29, offsetof(mavlink_ais_vessel_t, dimension_port) }, \ - { "dimension_starboard", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_ais_vessel_t, dimension_starboard) }, \ - { "callsign", NULL, MAVLINK_TYPE_CHAR, 7, 31, offsetof(mavlink_ais_vessel_t, callsign) }, \ - { "name", NULL, MAVLINK_TYPE_CHAR, 20, 38, offsetof(mavlink_ais_vessel_t, name) }, \ - { "tslc", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_ais_vessel_t, tslc) }, \ - { "flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_ais_vessel_t, flags) }, \ - } \ -} -#endif - -/** - * @brief Pack a ais_vessel message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param MMSI Mobile Marine Service Identifier, 9 decimal digits - * @param lat [degE7] Latitude - * @param lon [degE7] Longitude - * @param COG [cdeg] Course over ground - * @param heading [cdeg] True heading - * @param velocity [cm/s] Speed over ground - * @param turn_rate [cdeg/s] Turn rate - * @param navigational_status Navigational status - * @param type Type of vessels - * @param dimension_bow [m] Distance from lat/lon location to bow - * @param dimension_stern [m] Distance from lat/lon location to stern - * @param dimension_port [m] Distance from lat/lon location to port side - * @param dimension_starboard [m] Distance from lat/lon location to starboard side - * @param callsign The vessel callsign - * @param name The vessel name - * @param tslc [s] Time since last communication in seconds - * @param flags Bitmask to indicate various statuses including valid data fields - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_ais_vessel_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint32_t MMSI, int32_t lat, int32_t lon, uint16_t COG, uint16_t heading, uint16_t velocity, int8_t turn_rate, uint8_t navigational_status, uint8_t type, uint16_t dimension_bow, uint16_t dimension_stern, uint8_t dimension_port, uint8_t dimension_starboard, const char *callsign, const char *name, uint16_t tslc, uint16_t flags) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_AIS_VESSEL_LEN]; - _mav_put_uint32_t(buf, 0, MMSI); - _mav_put_int32_t(buf, 4, lat); - _mav_put_int32_t(buf, 8, lon); - _mav_put_uint16_t(buf, 12, COG); - _mav_put_uint16_t(buf, 14, heading); - _mav_put_uint16_t(buf, 16, velocity); - _mav_put_uint16_t(buf, 18, dimension_bow); - _mav_put_uint16_t(buf, 20, dimension_stern); - _mav_put_uint16_t(buf, 22, tslc); - _mav_put_uint16_t(buf, 24, flags); - _mav_put_int8_t(buf, 26, turn_rate); - _mav_put_uint8_t(buf, 27, navigational_status); - _mav_put_uint8_t(buf, 28, type); - _mav_put_uint8_t(buf, 29, dimension_port); - _mav_put_uint8_t(buf, 30, dimension_starboard); - _mav_put_char_array(buf, 31, callsign, 7); - _mav_put_char_array(buf, 38, name, 20); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_AIS_VESSEL_LEN); -#else - mavlink_ais_vessel_t packet; - packet.MMSI = MMSI; - packet.lat = lat; - packet.lon = lon; - packet.COG = COG; - packet.heading = heading; - packet.velocity = velocity; - packet.dimension_bow = dimension_bow; - packet.dimension_stern = dimension_stern; - packet.tslc = tslc; - packet.flags = flags; - packet.turn_rate = turn_rate; - packet.navigational_status = navigational_status; - packet.type = type; - packet.dimension_port = dimension_port; - packet.dimension_starboard = dimension_starboard; - mav_array_memcpy(packet.callsign, callsign, sizeof(char)*7); - mav_array_memcpy(packet.name, name, sizeof(char)*20); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_AIS_VESSEL_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_AIS_VESSEL; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_AIS_VESSEL_MIN_LEN, MAVLINK_MSG_ID_AIS_VESSEL_LEN, MAVLINK_MSG_ID_AIS_VESSEL_CRC); -} - -/** - * @brief Pack a ais_vessel message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param MMSI Mobile Marine Service Identifier, 9 decimal digits - * @param lat [degE7] Latitude - * @param lon [degE7] Longitude - * @param COG [cdeg] Course over ground - * @param heading [cdeg] True heading - * @param velocity [cm/s] Speed over ground - * @param turn_rate [cdeg/s] Turn rate - * @param navigational_status Navigational status - * @param type Type of vessels - * @param dimension_bow [m] Distance from lat/lon location to bow - * @param dimension_stern [m] Distance from lat/lon location to stern - * @param dimension_port [m] Distance from lat/lon location to port side - * @param dimension_starboard [m] Distance from lat/lon location to starboard side - * @param callsign The vessel callsign - * @param name The vessel name - * @param tslc [s] Time since last communication in seconds - * @param flags Bitmask to indicate various statuses including valid data fields - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_ais_vessel_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint32_t MMSI,int32_t lat,int32_t lon,uint16_t COG,uint16_t heading,uint16_t velocity,int8_t turn_rate,uint8_t navigational_status,uint8_t type,uint16_t dimension_bow,uint16_t dimension_stern,uint8_t dimension_port,uint8_t dimension_starboard,const char *callsign,const char *name,uint16_t tslc,uint16_t flags) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_AIS_VESSEL_LEN]; - _mav_put_uint32_t(buf, 0, MMSI); - _mav_put_int32_t(buf, 4, lat); - _mav_put_int32_t(buf, 8, lon); - _mav_put_uint16_t(buf, 12, COG); - _mav_put_uint16_t(buf, 14, heading); - _mav_put_uint16_t(buf, 16, velocity); - _mav_put_uint16_t(buf, 18, dimension_bow); - _mav_put_uint16_t(buf, 20, dimension_stern); - _mav_put_uint16_t(buf, 22, tslc); - _mav_put_uint16_t(buf, 24, flags); - _mav_put_int8_t(buf, 26, turn_rate); - _mav_put_uint8_t(buf, 27, navigational_status); - _mav_put_uint8_t(buf, 28, type); - _mav_put_uint8_t(buf, 29, dimension_port); - _mav_put_uint8_t(buf, 30, dimension_starboard); - _mav_put_char_array(buf, 31, callsign, 7); - _mav_put_char_array(buf, 38, name, 20); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_AIS_VESSEL_LEN); -#else - mavlink_ais_vessel_t packet; - packet.MMSI = MMSI; - packet.lat = lat; - packet.lon = lon; - packet.COG = COG; - packet.heading = heading; - packet.velocity = velocity; - packet.dimension_bow = dimension_bow; - packet.dimension_stern = dimension_stern; - packet.tslc = tslc; - packet.flags = flags; - packet.turn_rate = turn_rate; - packet.navigational_status = navigational_status; - packet.type = type; - packet.dimension_port = dimension_port; - packet.dimension_starboard = dimension_starboard; - mav_array_memcpy(packet.callsign, callsign, sizeof(char)*7); - mav_array_memcpy(packet.name, name, sizeof(char)*20); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_AIS_VESSEL_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_AIS_VESSEL; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_AIS_VESSEL_MIN_LEN, MAVLINK_MSG_ID_AIS_VESSEL_LEN, MAVLINK_MSG_ID_AIS_VESSEL_CRC); -} - -/** - * @brief Encode a ais_vessel struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param ais_vessel C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_ais_vessel_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_ais_vessel_t* ais_vessel) -{ - return mavlink_msg_ais_vessel_pack(system_id, component_id, msg, ais_vessel->MMSI, ais_vessel->lat, ais_vessel->lon, ais_vessel->COG, ais_vessel->heading, ais_vessel->velocity, ais_vessel->turn_rate, ais_vessel->navigational_status, ais_vessel->type, ais_vessel->dimension_bow, ais_vessel->dimension_stern, ais_vessel->dimension_port, ais_vessel->dimension_starboard, ais_vessel->callsign, ais_vessel->name, ais_vessel->tslc, ais_vessel->flags); -} - -/** - * @brief Encode a ais_vessel struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param ais_vessel C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_ais_vessel_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_ais_vessel_t* ais_vessel) -{ - return mavlink_msg_ais_vessel_pack_chan(system_id, component_id, chan, msg, ais_vessel->MMSI, ais_vessel->lat, ais_vessel->lon, ais_vessel->COG, ais_vessel->heading, ais_vessel->velocity, ais_vessel->turn_rate, ais_vessel->navigational_status, ais_vessel->type, ais_vessel->dimension_bow, ais_vessel->dimension_stern, ais_vessel->dimension_port, ais_vessel->dimension_starboard, ais_vessel->callsign, ais_vessel->name, ais_vessel->tslc, ais_vessel->flags); -} - -/** - * @brief Send a ais_vessel message - * @param chan MAVLink channel to send the message - * - * @param MMSI Mobile Marine Service Identifier, 9 decimal digits - * @param lat [degE7] Latitude - * @param lon [degE7] Longitude - * @param COG [cdeg] Course over ground - * @param heading [cdeg] True heading - * @param velocity [cm/s] Speed over ground - * @param turn_rate [cdeg/s] Turn rate - * @param navigational_status Navigational status - * @param type Type of vessels - * @param dimension_bow [m] Distance from lat/lon location to bow - * @param dimension_stern [m] Distance from lat/lon location to stern - * @param dimension_port [m] Distance from lat/lon location to port side - * @param dimension_starboard [m] Distance from lat/lon location to starboard side - * @param callsign The vessel callsign - * @param name The vessel name - * @param tslc [s] Time since last communication in seconds - * @param flags Bitmask to indicate various statuses including valid data fields - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_ais_vessel_send(mavlink_channel_t chan, uint32_t MMSI, int32_t lat, int32_t lon, uint16_t COG, uint16_t heading, uint16_t velocity, int8_t turn_rate, uint8_t navigational_status, uint8_t type, uint16_t dimension_bow, uint16_t dimension_stern, uint8_t dimension_port, uint8_t dimension_starboard, const char *callsign, const char *name, uint16_t tslc, uint16_t flags) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_AIS_VESSEL_LEN]; - _mav_put_uint32_t(buf, 0, MMSI); - _mav_put_int32_t(buf, 4, lat); - _mav_put_int32_t(buf, 8, lon); - _mav_put_uint16_t(buf, 12, COG); - _mav_put_uint16_t(buf, 14, heading); - _mav_put_uint16_t(buf, 16, velocity); - _mav_put_uint16_t(buf, 18, dimension_bow); - _mav_put_uint16_t(buf, 20, dimension_stern); - _mav_put_uint16_t(buf, 22, tslc); - _mav_put_uint16_t(buf, 24, flags); - _mav_put_int8_t(buf, 26, turn_rate); - _mav_put_uint8_t(buf, 27, navigational_status); - _mav_put_uint8_t(buf, 28, type); - _mav_put_uint8_t(buf, 29, dimension_port); - _mav_put_uint8_t(buf, 30, dimension_starboard); - _mav_put_char_array(buf, 31, callsign, 7); - _mav_put_char_array(buf, 38, name, 20); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AIS_VESSEL, buf, MAVLINK_MSG_ID_AIS_VESSEL_MIN_LEN, MAVLINK_MSG_ID_AIS_VESSEL_LEN, MAVLINK_MSG_ID_AIS_VESSEL_CRC); -#else - mavlink_ais_vessel_t packet; - packet.MMSI = MMSI; - packet.lat = lat; - packet.lon = lon; - packet.COG = COG; - packet.heading = heading; - packet.velocity = velocity; - packet.dimension_bow = dimension_bow; - packet.dimension_stern = dimension_stern; - packet.tslc = tslc; - packet.flags = flags; - packet.turn_rate = turn_rate; - packet.navigational_status = navigational_status; - packet.type = type; - packet.dimension_port = dimension_port; - packet.dimension_starboard = dimension_starboard; - mav_array_memcpy(packet.callsign, callsign, sizeof(char)*7); - mav_array_memcpy(packet.name, name, sizeof(char)*20); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AIS_VESSEL, (const char *)&packet, MAVLINK_MSG_ID_AIS_VESSEL_MIN_LEN, MAVLINK_MSG_ID_AIS_VESSEL_LEN, MAVLINK_MSG_ID_AIS_VESSEL_CRC); -#endif -} - -/** - * @brief Send a ais_vessel message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_ais_vessel_send_struct(mavlink_channel_t chan, const mavlink_ais_vessel_t* ais_vessel) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_ais_vessel_send(chan, ais_vessel->MMSI, ais_vessel->lat, ais_vessel->lon, ais_vessel->COG, ais_vessel->heading, ais_vessel->velocity, ais_vessel->turn_rate, ais_vessel->navigational_status, ais_vessel->type, ais_vessel->dimension_bow, ais_vessel->dimension_stern, ais_vessel->dimension_port, ais_vessel->dimension_starboard, ais_vessel->callsign, ais_vessel->name, ais_vessel->tslc, ais_vessel->flags); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AIS_VESSEL, (const char *)ais_vessel, MAVLINK_MSG_ID_AIS_VESSEL_MIN_LEN, MAVLINK_MSG_ID_AIS_VESSEL_LEN, MAVLINK_MSG_ID_AIS_VESSEL_CRC); -#endif -} - -#if MAVLINK_MSG_ID_AIS_VESSEL_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_ais_vessel_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t MMSI, int32_t lat, int32_t lon, uint16_t COG, uint16_t heading, uint16_t velocity, int8_t turn_rate, uint8_t navigational_status, uint8_t type, uint16_t dimension_bow, uint16_t dimension_stern, uint8_t dimension_port, uint8_t dimension_starboard, const char *callsign, const char *name, uint16_t tslc, uint16_t flags) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, MMSI); - _mav_put_int32_t(buf, 4, lat); - _mav_put_int32_t(buf, 8, lon); - _mav_put_uint16_t(buf, 12, COG); - _mav_put_uint16_t(buf, 14, heading); - _mav_put_uint16_t(buf, 16, velocity); - _mav_put_uint16_t(buf, 18, dimension_bow); - _mav_put_uint16_t(buf, 20, dimension_stern); - _mav_put_uint16_t(buf, 22, tslc); - _mav_put_uint16_t(buf, 24, flags); - _mav_put_int8_t(buf, 26, turn_rate); - _mav_put_uint8_t(buf, 27, navigational_status); - _mav_put_uint8_t(buf, 28, type); - _mav_put_uint8_t(buf, 29, dimension_port); - _mav_put_uint8_t(buf, 30, dimension_starboard); - _mav_put_char_array(buf, 31, callsign, 7); - _mav_put_char_array(buf, 38, name, 20); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AIS_VESSEL, buf, MAVLINK_MSG_ID_AIS_VESSEL_MIN_LEN, MAVLINK_MSG_ID_AIS_VESSEL_LEN, MAVLINK_MSG_ID_AIS_VESSEL_CRC); -#else - mavlink_ais_vessel_t *packet = (mavlink_ais_vessel_t *)msgbuf; - packet->MMSI = MMSI; - packet->lat = lat; - packet->lon = lon; - packet->COG = COG; - packet->heading = heading; - packet->velocity = velocity; - packet->dimension_bow = dimension_bow; - packet->dimension_stern = dimension_stern; - packet->tslc = tslc; - packet->flags = flags; - packet->turn_rate = turn_rate; - packet->navigational_status = navigational_status; - packet->type = type; - packet->dimension_port = dimension_port; - packet->dimension_starboard = dimension_starboard; - mav_array_memcpy(packet->callsign, callsign, sizeof(char)*7); - mav_array_memcpy(packet->name, name, sizeof(char)*20); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AIS_VESSEL, (const char *)packet, MAVLINK_MSG_ID_AIS_VESSEL_MIN_LEN, MAVLINK_MSG_ID_AIS_VESSEL_LEN, MAVLINK_MSG_ID_AIS_VESSEL_CRC); -#endif -} -#endif - -#endif - -// MESSAGE AIS_VESSEL UNPACKING - - -/** - * @brief Get field MMSI from ais_vessel message - * - * @return Mobile Marine Service Identifier, 9 decimal digits - */ -static inline uint32_t mavlink_msg_ais_vessel_get_MMSI(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field lat from ais_vessel message - * - * @return [degE7] Latitude - */ -static inline int32_t mavlink_msg_ais_vessel_get_lat(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 4); -} - -/** - * @brief Get field lon from ais_vessel message - * - * @return [degE7] Longitude - */ -static inline int32_t mavlink_msg_ais_vessel_get_lon(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 8); -} - -/** - * @brief Get field COG from ais_vessel message - * - * @return [cdeg] Course over ground - */ -static inline uint16_t mavlink_msg_ais_vessel_get_COG(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 12); -} - -/** - * @brief Get field heading from ais_vessel message - * - * @return [cdeg] True heading - */ -static inline uint16_t mavlink_msg_ais_vessel_get_heading(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 14); -} - -/** - * @brief Get field velocity from ais_vessel message - * - * @return [cm/s] Speed over ground - */ -static inline uint16_t mavlink_msg_ais_vessel_get_velocity(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 16); -} - -/** - * @brief Get field turn_rate from ais_vessel message - * - * @return [cdeg/s] Turn rate - */ -static inline int8_t mavlink_msg_ais_vessel_get_turn_rate(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int8_t(msg, 26); -} - -/** - * @brief Get field navigational_status from ais_vessel message - * - * @return Navigational status - */ -static inline uint8_t mavlink_msg_ais_vessel_get_navigational_status(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 27); -} - -/** - * @brief Get field type from ais_vessel message - * - * @return Type of vessels - */ -static inline uint8_t mavlink_msg_ais_vessel_get_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 28); -} - -/** - * @brief Get field dimension_bow from ais_vessel message - * - * @return [m] Distance from lat/lon location to bow - */ -static inline uint16_t mavlink_msg_ais_vessel_get_dimension_bow(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 18); -} - -/** - * @brief Get field dimension_stern from ais_vessel message - * - * @return [m] Distance from lat/lon location to stern - */ -static inline uint16_t mavlink_msg_ais_vessel_get_dimension_stern(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 20); -} - -/** - * @brief Get field dimension_port from ais_vessel message - * - * @return [m] Distance from lat/lon location to port side - */ -static inline uint8_t mavlink_msg_ais_vessel_get_dimension_port(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 29); -} - -/** - * @brief Get field dimension_starboard from ais_vessel message - * - * @return [m] Distance from lat/lon location to starboard side - */ -static inline uint8_t mavlink_msg_ais_vessel_get_dimension_starboard(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 30); -} - -/** - * @brief Get field callsign from ais_vessel message - * - * @return The vessel callsign - */ -static inline uint16_t mavlink_msg_ais_vessel_get_callsign(const mavlink_message_t* msg, char *callsign) -{ - return _MAV_RETURN_char_array(msg, callsign, 7, 31); -} - -/** - * @brief Get field name from ais_vessel message - * - * @return The vessel name - */ -static inline uint16_t mavlink_msg_ais_vessel_get_name(const mavlink_message_t* msg, char *name) -{ - return _MAV_RETURN_char_array(msg, name, 20, 38); -} - -/** - * @brief Get field tslc from ais_vessel message - * - * @return [s] Time since last communication in seconds - */ -static inline uint16_t mavlink_msg_ais_vessel_get_tslc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 22); -} - -/** - * @brief Get field flags from ais_vessel message - * - * @return Bitmask to indicate various statuses including valid data fields - */ -static inline uint16_t mavlink_msg_ais_vessel_get_flags(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 24); -} - -/** - * @brief Decode a ais_vessel message into a struct - * - * @param msg The message to decode - * @param ais_vessel C-struct to decode the message contents into - */ -static inline void mavlink_msg_ais_vessel_decode(const mavlink_message_t* msg, mavlink_ais_vessel_t* ais_vessel) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - ais_vessel->MMSI = mavlink_msg_ais_vessel_get_MMSI(msg); - ais_vessel->lat = mavlink_msg_ais_vessel_get_lat(msg); - ais_vessel->lon = mavlink_msg_ais_vessel_get_lon(msg); - ais_vessel->COG = mavlink_msg_ais_vessel_get_COG(msg); - ais_vessel->heading = mavlink_msg_ais_vessel_get_heading(msg); - ais_vessel->velocity = mavlink_msg_ais_vessel_get_velocity(msg); - ais_vessel->dimension_bow = mavlink_msg_ais_vessel_get_dimension_bow(msg); - ais_vessel->dimension_stern = mavlink_msg_ais_vessel_get_dimension_stern(msg); - ais_vessel->tslc = mavlink_msg_ais_vessel_get_tslc(msg); - ais_vessel->flags = mavlink_msg_ais_vessel_get_flags(msg); - ais_vessel->turn_rate = mavlink_msg_ais_vessel_get_turn_rate(msg); - ais_vessel->navigational_status = mavlink_msg_ais_vessel_get_navigational_status(msg); - ais_vessel->type = mavlink_msg_ais_vessel_get_type(msg); - ais_vessel->dimension_port = mavlink_msg_ais_vessel_get_dimension_port(msg); - ais_vessel->dimension_starboard = mavlink_msg_ais_vessel_get_dimension_starboard(msg); - mavlink_msg_ais_vessel_get_callsign(msg, ais_vessel->callsign); - mavlink_msg_ais_vessel_get_name(msg, ais_vessel->name); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_AIS_VESSEL_LEN? msg->len : MAVLINK_MSG_ID_AIS_VESSEL_LEN; - memset(ais_vessel, 0, MAVLINK_MSG_ID_AIS_VESSEL_LEN); - memcpy(ais_vessel, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_altitude.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_altitude.h deleted file mode 100644 index 41f61274..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_altitude.h +++ /dev/null @@ -1,363 +0,0 @@ -#pragma once -// MESSAGE ALTITUDE PACKING - -#define MAVLINK_MSG_ID_ALTITUDE 141 - - -typedef struct __mavlink_altitude_t { - uint64_t time_usec; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/ - float altitude_monotonic; /*< [m] This altitude measure is initialized on system boot and monotonic (it is never reset, but represents the local altitude change). The only guarantee on this field is that it will never be reset and is consistent within a flight. The recommended value for this field is the uncorrected barometric altitude at boot time. This altitude will also drift and vary between flights.*/ - float altitude_amsl; /*< [m] This altitude measure is strictly above mean sea level and might be non-monotonic (it might reset on events like GPS lock or when a new QNH value is set). It should be the altitude to which global altitude waypoints are compared to. Note that it is *not* the GPS altitude, however, most GPS modules already output MSL by default and not the WGS84 altitude.*/ - float altitude_local; /*< [m] This is the local altitude in the local coordinate frame. It is not the altitude above home, but in reference to the coordinate origin (0, 0, 0). It is up-positive.*/ - float altitude_relative; /*< [m] This is the altitude above the home position. It resets on each change of the current home position.*/ - float altitude_terrain; /*< [m] This is the altitude above terrain. It might be fed by a terrain database or an altimeter. Values smaller than -1000 should be interpreted as unknown.*/ - float bottom_clearance; /*< [m] This is not the altitude, but the clear space below the system according to the fused clearance estimate. It generally should max out at the maximum range of e.g. the laser altimeter. It is generally a moving target. A negative value indicates no measurement available.*/ -} mavlink_altitude_t; - -#define MAVLINK_MSG_ID_ALTITUDE_LEN 32 -#define MAVLINK_MSG_ID_ALTITUDE_MIN_LEN 32 -#define MAVLINK_MSG_ID_141_LEN 32 -#define MAVLINK_MSG_ID_141_MIN_LEN 32 - -#define MAVLINK_MSG_ID_ALTITUDE_CRC 47 -#define MAVLINK_MSG_ID_141_CRC 47 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_ALTITUDE { \ - 141, \ - "ALTITUDE", \ - 7, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_altitude_t, time_usec) }, \ - { "altitude_monotonic", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_altitude_t, altitude_monotonic) }, \ - { "altitude_amsl", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_altitude_t, altitude_amsl) }, \ - { "altitude_local", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_altitude_t, altitude_local) }, \ - { "altitude_relative", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_altitude_t, altitude_relative) }, \ - { "altitude_terrain", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_altitude_t, altitude_terrain) }, \ - { "bottom_clearance", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_altitude_t, bottom_clearance) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_ALTITUDE { \ - "ALTITUDE", \ - 7, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_altitude_t, time_usec) }, \ - { "altitude_monotonic", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_altitude_t, altitude_monotonic) }, \ - { "altitude_amsl", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_altitude_t, altitude_amsl) }, \ - { "altitude_local", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_altitude_t, altitude_local) }, \ - { "altitude_relative", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_altitude_t, altitude_relative) }, \ - { "altitude_terrain", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_altitude_t, altitude_terrain) }, \ - { "bottom_clearance", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_altitude_t, bottom_clearance) }, \ - } \ -} -#endif - -/** - * @brief Pack a altitude message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @param altitude_monotonic [m] This altitude measure is initialized on system boot and monotonic (it is never reset, but represents the local altitude change). The only guarantee on this field is that it will never be reset and is consistent within a flight. The recommended value for this field is the uncorrected barometric altitude at boot time. This altitude will also drift and vary between flights. - * @param altitude_amsl [m] This altitude measure is strictly above mean sea level and might be non-monotonic (it might reset on events like GPS lock or when a new QNH value is set). It should be the altitude to which global altitude waypoints are compared to. Note that it is *not* the GPS altitude, however, most GPS modules already output MSL by default and not the WGS84 altitude. - * @param altitude_local [m] This is the local altitude in the local coordinate frame. It is not the altitude above home, but in reference to the coordinate origin (0, 0, 0). It is up-positive. - * @param altitude_relative [m] This is the altitude above the home position. It resets on each change of the current home position. - * @param altitude_terrain [m] This is the altitude above terrain. It might be fed by a terrain database or an altimeter. Values smaller than -1000 should be interpreted as unknown. - * @param bottom_clearance [m] This is not the altitude, but the clear space below the system according to the fused clearance estimate. It generally should max out at the maximum range of e.g. the laser altimeter. It is generally a moving target. A negative value indicates no measurement available. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_altitude_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint64_t time_usec, float altitude_monotonic, float altitude_amsl, float altitude_local, float altitude_relative, float altitude_terrain, float bottom_clearance) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_ALTITUDE_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, altitude_monotonic); - _mav_put_float(buf, 12, altitude_amsl); - _mav_put_float(buf, 16, altitude_local); - _mav_put_float(buf, 20, altitude_relative); - _mav_put_float(buf, 24, altitude_terrain); - _mav_put_float(buf, 28, bottom_clearance); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ALTITUDE_LEN); -#else - mavlink_altitude_t packet; - packet.time_usec = time_usec; - packet.altitude_monotonic = altitude_monotonic; - packet.altitude_amsl = altitude_amsl; - packet.altitude_local = altitude_local; - packet.altitude_relative = altitude_relative; - packet.altitude_terrain = altitude_terrain; - packet.bottom_clearance = bottom_clearance; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ALTITUDE_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_ALTITUDE; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ALTITUDE_MIN_LEN, MAVLINK_MSG_ID_ALTITUDE_LEN, MAVLINK_MSG_ID_ALTITUDE_CRC); -} - -/** - * @brief Pack a altitude message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @param altitude_monotonic [m] This altitude measure is initialized on system boot and monotonic (it is never reset, but represents the local altitude change). The only guarantee on this field is that it will never be reset and is consistent within a flight. The recommended value for this field is the uncorrected barometric altitude at boot time. This altitude will also drift and vary between flights. - * @param altitude_amsl [m] This altitude measure is strictly above mean sea level and might be non-monotonic (it might reset on events like GPS lock or when a new QNH value is set). It should be the altitude to which global altitude waypoints are compared to. Note that it is *not* the GPS altitude, however, most GPS modules already output MSL by default and not the WGS84 altitude. - * @param altitude_local [m] This is the local altitude in the local coordinate frame. It is not the altitude above home, but in reference to the coordinate origin (0, 0, 0). It is up-positive. - * @param altitude_relative [m] This is the altitude above the home position. It resets on each change of the current home position. - * @param altitude_terrain [m] This is the altitude above terrain. It might be fed by a terrain database or an altimeter. Values smaller than -1000 should be interpreted as unknown. - * @param bottom_clearance [m] This is not the altitude, but the clear space below the system according to the fused clearance estimate. It generally should max out at the maximum range of e.g. the laser altimeter. It is generally a moving target. A negative value indicates no measurement available. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_altitude_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint64_t time_usec,float altitude_monotonic,float altitude_amsl,float altitude_local,float altitude_relative,float altitude_terrain,float bottom_clearance) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_ALTITUDE_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, altitude_monotonic); - _mav_put_float(buf, 12, altitude_amsl); - _mav_put_float(buf, 16, altitude_local); - _mav_put_float(buf, 20, altitude_relative); - _mav_put_float(buf, 24, altitude_terrain); - _mav_put_float(buf, 28, bottom_clearance); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ALTITUDE_LEN); -#else - mavlink_altitude_t packet; - packet.time_usec = time_usec; - packet.altitude_monotonic = altitude_monotonic; - packet.altitude_amsl = altitude_amsl; - packet.altitude_local = altitude_local; - packet.altitude_relative = altitude_relative; - packet.altitude_terrain = altitude_terrain; - packet.bottom_clearance = bottom_clearance; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ALTITUDE_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_ALTITUDE; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ALTITUDE_MIN_LEN, MAVLINK_MSG_ID_ALTITUDE_LEN, MAVLINK_MSG_ID_ALTITUDE_CRC); -} - -/** - * @brief Encode a altitude struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param altitude C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_altitude_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_altitude_t* altitude) -{ - return mavlink_msg_altitude_pack(system_id, component_id, msg, altitude->time_usec, altitude->altitude_monotonic, altitude->altitude_amsl, altitude->altitude_local, altitude->altitude_relative, altitude->altitude_terrain, altitude->bottom_clearance); -} - -/** - * @brief Encode a altitude struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param altitude C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_altitude_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_altitude_t* altitude) -{ - return mavlink_msg_altitude_pack_chan(system_id, component_id, chan, msg, altitude->time_usec, altitude->altitude_monotonic, altitude->altitude_amsl, altitude->altitude_local, altitude->altitude_relative, altitude->altitude_terrain, altitude->bottom_clearance); -} - -/** - * @brief Send a altitude message - * @param chan MAVLink channel to send the message - * - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @param altitude_monotonic [m] This altitude measure is initialized on system boot and monotonic (it is never reset, but represents the local altitude change). The only guarantee on this field is that it will never be reset and is consistent within a flight. The recommended value for this field is the uncorrected barometric altitude at boot time. This altitude will also drift and vary between flights. - * @param altitude_amsl [m] This altitude measure is strictly above mean sea level and might be non-monotonic (it might reset on events like GPS lock or when a new QNH value is set). It should be the altitude to which global altitude waypoints are compared to. Note that it is *not* the GPS altitude, however, most GPS modules already output MSL by default and not the WGS84 altitude. - * @param altitude_local [m] This is the local altitude in the local coordinate frame. It is not the altitude above home, but in reference to the coordinate origin (0, 0, 0). It is up-positive. - * @param altitude_relative [m] This is the altitude above the home position. It resets on each change of the current home position. - * @param altitude_terrain [m] This is the altitude above terrain. It might be fed by a terrain database or an altimeter. Values smaller than -1000 should be interpreted as unknown. - * @param bottom_clearance [m] This is not the altitude, but the clear space below the system according to the fused clearance estimate. It generally should max out at the maximum range of e.g. the laser altimeter. It is generally a moving target. A negative value indicates no measurement available. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_altitude_send(mavlink_channel_t chan, uint64_t time_usec, float altitude_monotonic, float altitude_amsl, float altitude_local, float altitude_relative, float altitude_terrain, float bottom_clearance) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_ALTITUDE_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, altitude_monotonic); - _mav_put_float(buf, 12, altitude_amsl); - _mav_put_float(buf, 16, altitude_local); - _mav_put_float(buf, 20, altitude_relative); - _mav_put_float(buf, 24, altitude_terrain); - _mav_put_float(buf, 28, bottom_clearance); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ALTITUDE, buf, MAVLINK_MSG_ID_ALTITUDE_MIN_LEN, MAVLINK_MSG_ID_ALTITUDE_LEN, MAVLINK_MSG_ID_ALTITUDE_CRC); -#else - mavlink_altitude_t packet; - packet.time_usec = time_usec; - packet.altitude_monotonic = altitude_monotonic; - packet.altitude_amsl = altitude_amsl; - packet.altitude_local = altitude_local; - packet.altitude_relative = altitude_relative; - packet.altitude_terrain = altitude_terrain; - packet.bottom_clearance = bottom_clearance; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ALTITUDE, (const char *)&packet, MAVLINK_MSG_ID_ALTITUDE_MIN_LEN, MAVLINK_MSG_ID_ALTITUDE_LEN, MAVLINK_MSG_ID_ALTITUDE_CRC); -#endif -} - -/** - * @brief Send a altitude message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_altitude_send_struct(mavlink_channel_t chan, const mavlink_altitude_t* altitude) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_altitude_send(chan, altitude->time_usec, altitude->altitude_monotonic, altitude->altitude_amsl, altitude->altitude_local, altitude->altitude_relative, altitude->altitude_terrain, altitude->bottom_clearance); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ALTITUDE, (const char *)altitude, MAVLINK_MSG_ID_ALTITUDE_MIN_LEN, MAVLINK_MSG_ID_ALTITUDE_LEN, MAVLINK_MSG_ID_ALTITUDE_CRC); -#endif -} - -#if MAVLINK_MSG_ID_ALTITUDE_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_altitude_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, float altitude_monotonic, float altitude_amsl, float altitude_local, float altitude_relative, float altitude_terrain, float bottom_clearance) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, altitude_monotonic); - _mav_put_float(buf, 12, altitude_amsl); - _mav_put_float(buf, 16, altitude_local); - _mav_put_float(buf, 20, altitude_relative); - _mav_put_float(buf, 24, altitude_terrain); - _mav_put_float(buf, 28, bottom_clearance); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ALTITUDE, buf, MAVLINK_MSG_ID_ALTITUDE_MIN_LEN, MAVLINK_MSG_ID_ALTITUDE_LEN, MAVLINK_MSG_ID_ALTITUDE_CRC); -#else - mavlink_altitude_t *packet = (mavlink_altitude_t *)msgbuf; - packet->time_usec = time_usec; - packet->altitude_monotonic = altitude_monotonic; - packet->altitude_amsl = altitude_amsl; - packet->altitude_local = altitude_local; - packet->altitude_relative = altitude_relative; - packet->altitude_terrain = altitude_terrain; - packet->bottom_clearance = bottom_clearance; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ALTITUDE, (const char *)packet, MAVLINK_MSG_ID_ALTITUDE_MIN_LEN, MAVLINK_MSG_ID_ALTITUDE_LEN, MAVLINK_MSG_ID_ALTITUDE_CRC); -#endif -} -#endif - -#endif - -// MESSAGE ALTITUDE UNPACKING - - -/** - * @brief Get field time_usec from altitude message - * - * @return [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - */ -static inline uint64_t mavlink_msg_altitude_get_time_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field altitude_monotonic from altitude message - * - * @return [m] This altitude measure is initialized on system boot and monotonic (it is never reset, but represents the local altitude change). The only guarantee on this field is that it will never be reset and is consistent within a flight. The recommended value for this field is the uncorrected barometric altitude at boot time. This altitude will also drift and vary between flights. - */ -static inline float mavlink_msg_altitude_get_altitude_monotonic(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field altitude_amsl from altitude message - * - * @return [m] This altitude measure is strictly above mean sea level and might be non-monotonic (it might reset on events like GPS lock or when a new QNH value is set). It should be the altitude to which global altitude waypoints are compared to. Note that it is *not* the GPS altitude, however, most GPS modules already output MSL by default and not the WGS84 altitude. - */ -static inline float mavlink_msg_altitude_get_altitude_amsl(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field altitude_local from altitude message - * - * @return [m] This is the local altitude in the local coordinate frame. It is not the altitude above home, but in reference to the coordinate origin (0, 0, 0). It is up-positive. - */ -static inline float mavlink_msg_altitude_get_altitude_local(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field altitude_relative from altitude message - * - * @return [m] This is the altitude above the home position. It resets on each change of the current home position. - */ -static inline float mavlink_msg_altitude_get_altitude_relative(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Get field altitude_terrain from altitude message - * - * @return [m] This is the altitude above terrain. It might be fed by a terrain database or an altimeter. Values smaller than -1000 should be interpreted as unknown. - */ -static inline float mavlink_msg_altitude_get_altitude_terrain(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Get field bottom_clearance from altitude message - * - * @return [m] This is not the altitude, but the clear space below the system according to the fused clearance estimate. It generally should max out at the maximum range of e.g. the laser altimeter. It is generally a moving target. A negative value indicates no measurement available. - */ -static inline float mavlink_msg_altitude_get_bottom_clearance(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 28); -} - -/** - * @brief Decode a altitude message into a struct - * - * @param msg The message to decode - * @param altitude C-struct to decode the message contents into - */ -static inline void mavlink_msg_altitude_decode(const mavlink_message_t* msg, mavlink_altitude_t* altitude) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - altitude->time_usec = mavlink_msg_altitude_get_time_usec(msg); - altitude->altitude_monotonic = mavlink_msg_altitude_get_altitude_monotonic(msg); - altitude->altitude_amsl = mavlink_msg_altitude_get_altitude_amsl(msg); - altitude->altitude_local = mavlink_msg_altitude_get_altitude_local(msg); - altitude->altitude_relative = mavlink_msg_altitude_get_altitude_relative(msg); - altitude->altitude_terrain = mavlink_msg_altitude_get_altitude_terrain(msg); - altitude->bottom_clearance = mavlink_msg_altitude_get_bottom_clearance(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_ALTITUDE_LEN? msg->len : MAVLINK_MSG_ID_ALTITUDE_LEN; - memset(altitude, 0, MAVLINK_MSG_ID_ALTITUDE_LEN); - memcpy(altitude, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_att_pos_mocap.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_att_pos_mocap.h deleted file mode 100644 index 277acc78..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_att_pos_mocap.h +++ /dev/null @@ -1,331 +0,0 @@ -#pragma once -// MESSAGE ATT_POS_MOCAP PACKING - -#define MAVLINK_MSG_ID_ATT_POS_MOCAP 138 - - -typedef struct __mavlink_att_pos_mocap_t { - uint64_t time_usec; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/ - float q[4]; /*< Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0)*/ - float x; /*< [m] X position (NED)*/ - float y; /*< [m] Y position (NED)*/ - float z; /*< [m] Z position (NED)*/ - float covariance[21]; /*< Row-major representation of a pose 6x6 cross-covariance matrix upper right triangle (states: x, y, z, roll, pitch, yaw; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array.*/ -} mavlink_att_pos_mocap_t; - -#define MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN 120 -#define MAVLINK_MSG_ID_ATT_POS_MOCAP_MIN_LEN 36 -#define MAVLINK_MSG_ID_138_LEN 120 -#define MAVLINK_MSG_ID_138_MIN_LEN 36 - -#define MAVLINK_MSG_ID_ATT_POS_MOCAP_CRC 109 -#define MAVLINK_MSG_ID_138_CRC 109 - -#define MAVLINK_MSG_ATT_POS_MOCAP_FIELD_Q_LEN 4 -#define MAVLINK_MSG_ATT_POS_MOCAP_FIELD_COVARIANCE_LEN 21 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_ATT_POS_MOCAP { \ - 138, \ - "ATT_POS_MOCAP", \ - 6, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_att_pos_mocap_t, time_usec) }, \ - { "q", NULL, MAVLINK_TYPE_FLOAT, 4, 8, offsetof(mavlink_att_pos_mocap_t, q) }, \ - { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_att_pos_mocap_t, x) }, \ - { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_att_pos_mocap_t, y) }, \ - { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_att_pos_mocap_t, z) }, \ - { "covariance", NULL, MAVLINK_TYPE_FLOAT, 21, 36, offsetof(mavlink_att_pos_mocap_t, covariance) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_ATT_POS_MOCAP { \ - "ATT_POS_MOCAP", \ - 6, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_att_pos_mocap_t, time_usec) }, \ - { "q", NULL, MAVLINK_TYPE_FLOAT, 4, 8, offsetof(mavlink_att_pos_mocap_t, q) }, \ - { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_att_pos_mocap_t, x) }, \ - { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_att_pos_mocap_t, y) }, \ - { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_att_pos_mocap_t, z) }, \ - { "covariance", NULL, MAVLINK_TYPE_FLOAT, 21, 36, offsetof(mavlink_att_pos_mocap_t, covariance) }, \ - } \ -} -#endif - -/** - * @brief Pack a att_pos_mocap message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @param q Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) - * @param x [m] X position (NED) - * @param y [m] Y position (NED) - * @param z [m] Z position (NED) - * @param covariance Row-major representation of a pose 6x6 cross-covariance matrix upper right triangle (states: x, y, z, roll, pitch, yaw; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_att_pos_mocap_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint64_t time_usec, const float *q, float x, float y, float z, const float *covariance) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 24, x); - _mav_put_float(buf, 28, y); - _mav_put_float(buf, 32, z); - _mav_put_float_array(buf, 8, q, 4); - _mav_put_float_array(buf, 36, covariance, 21); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN); -#else - mavlink_att_pos_mocap_t packet; - packet.time_usec = time_usec; - packet.x = x; - packet.y = y; - packet.z = z; - mav_array_memcpy(packet.q, q, sizeof(float)*4); - mav_array_memcpy(packet.covariance, covariance, sizeof(float)*21); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_ATT_POS_MOCAP; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ATT_POS_MOCAP_MIN_LEN, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN, MAVLINK_MSG_ID_ATT_POS_MOCAP_CRC); -} - -/** - * @brief Pack a att_pos_mocap message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @param q Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) - * @param x [m] X position (NED) - * @param y [m] Y position (NED) - * @param z [m] Z position (NED) - * @param covariance Row-major representation of a pose 6x6 cross-covariance matrix upper right triangle (states: x, y, z, roll, pitch, yaw; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_att_pos_mocap_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint64_t time_usec,const float *q,float x,float y,float z,const float *covariance) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 24, x); - _mav_put_float(buf, 28, y); - _mav_put_float(buf, 32, z); - _mav_put_float_array(buf, 8, q, 4); - _mav_put_float_array(buf, 36, covariance, 21); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN); -#else - mavlink_att_pos_mocap_t packet; - packet.time_usec = time_usec; - packet.x = x; - packet.y = y; - packet.z = z; - mav_array_memcpy(packet.q, q, sizeof(float)*4); - mav_array_memcpy(packet.covariance, covariance, sizeof(float)*21); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_ATT_POS_MOCAP; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ATT_POS_MOCAP_MIN_LEN, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN, MAVLINK_MSG_ID_ATT_POS_MOCAP_CRC); -} - -/** - * @brief Encode a att_pos_mocap struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param att_pos_mocap C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_att_pos_mocap_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_att_pos_mocap_t* att_pos_mocap) -{ - return mavlink_msg_att_pos_mocap_pack(system_id, component_id, msg, att_pos_mocap->time_usec, att_pos_mocap->q, att_pos_mocap->x, att_pos_mocap->y, att_pos_mocap->z, att_pos_mocap->covariance); -} - -/** - * @brief Encode a att_pos_mocap struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param att_pos_mocap C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_att_pos_mocap_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_att_pos_mocap_t* att_pos_mocap) -{ - return mavlink_msg_att_pos_mocap_pack_chan(system_id, component_id, chan, msg, att_pos_mocap->time_usec, att_pos_mocap->q, att_pos_mocap->x, att_pos_mocap->y, att_pos_mocap->z, att_pos_mocap->covariance); -} - -/** - * @brief Send a att_pos_mocap message - * @param chan MAVLink channel to send the message - * - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @param q Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) - * @param x [m] X position (NED) - * @param y [m] Y position (NED) - * @param z [m] Z position (NED) - * @param covariance Row-major representation of a pose 6x6 cross-covariance matrix upper right triangle (states: x, y, z, roll, pitch, yaw; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_att_pos_mocap_send(mavlink_channel_t chan, uint64_t time_usec, const float *q, float x, float y, float z, const float *covariance) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 24, x); - _mav_put_float(buf, 28, y); - _mav_put_float(buf, 32, z); - _mav_put_float_array(buf, 8, q, 4); - _mav_put_float_array(buf, 36, covariance, 21); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATT_POS_MOCAP, buf, MAVLINK_MSG_ID_ATT_POS_MOCAP_MIN_LEN, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN, MAVLINK_MSG_ID_ATT_POS_MOCAP_CRC); -#else - mavlink_att_pos_mocap_t packet; - packet.time_usec = time_usec; - packet.x = x; - packet.y = y; - packet.z = z; - mav_array_memcpy(packet.q, q, sizeof(float)*4); - mav_array_memcpy(packet.covariance, covariance, sizeof(float)*21); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATT_POS_MOCAP, (const char *)&packet, MAVLINK_MSG_ID_ATT_POS_MOCAP_MIN_LEN, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN, MAVLINK_MSG_ID_ATT_POS_MOCAP_CRC); -#endif -} - -/** - * @brief Send a att_pos_mocap message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_att_pos_mocap_send_struct(mavlink_channel_t chan, const mavlink_att_pos_mocap_t* att_pos_mocap) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_att_pos_mocap_send(chan, att_pos_mocap->time_usec, att_pos_mocap->q, att_pos_mocap->x, att_pos_mocap->y, att_pos_mocap->z, att_pos_mocap->covariance); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATT_POS_MOCAP, (const char *)att_pos_mocap, MAVLINK_MSG_ID_ATT_POS_MOCAP_MIN_LEN, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN, MAVLINK_MSG_ID_ATT_POS_MOCAP_CRC); -#endif -} - -#if MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_att_pos_mocap_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, const float *q, float x, float y, float z, const float *covariance) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 24, x); - _mav_put_float(buf, 28, y); - _mav_put_float(buf, 32, z); - _mav_put_float_array(buf, 8, q, 4); - _mav_put_float_array(buf, 36, covariance, 21); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATT_POS_MOCAP, buf, MAVLINK_MSG_ID_ATT_POS_MOCAP_MIN_LEN, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN, MAVLINK_MSG_ID_ATT_POS_MOCAP_CRC); -#else - mavlink_att_pos_mocap_t *packet = (mavlink_att_pos_mocap_t *)msgbuf; - packet->time_usec = time_usec; - packet->x = x; - packet->y = y; - packet->z = z; - mav_array_memcpy(packet->q, q, sizeof(float)*4); - mav_array_memcpy(packet->covariance, covariance, sizeof(float)*21); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATT_POS_MOCAP, (const char *)packet, MAVLINK_MSG_ID_ATT_POS_MOCAP_MIN_LEN, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN, MAVLINK_MSG_ID_ATT_POS_MOCAP_CRC); -#endif -} -#endif - -#endif - -// MESSAGE ATT_POS_MOCAP UNPACKING - - -/** - * @brief Get field time_usec from att_pos_mocap message - * - * @return [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - */ -static inline uint64_t mavlink_msg_att_pos_mocap_get_time_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field q from att_pos_mocap message - * - * @return Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) - */ -static inline uint16_t mavlink_msg_att_pos_mocap_get_q(const mavlink_message_t* msg, float *q) -{ - return _MAV_RETURN_float_array(msg, q, 4, 8); -} - -/** - * @brief Get field x from att_pos_mocap message - * - * @return [m] X position (NED) - */ -static inline float mavlink_msg_att_pos_mocap_get_x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Get field y from att_pos_mocap message - * - * @return [m] Y position (NED) - */ -static inline float mavlink_msg_att_pos_mocap_get_y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 28); -} - -/** - * @brief Get field z from att_pos_mocap message - * - * @return [m] Z position (NED) - */ -static inline float mavlink_msg_att_pos_mocap_get_z(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 32); -} - -/** - * @brief Get field covariance from att_pos_mocap message - * - * @return Row-major representation of a pose 6x6 cross-covariance matrix upper right triangle (states: x, y, z, roll, pitch, yaw; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array. - */ -static inline uint16_t mavlink_msg_att_pos_mocap_get_covariance(const mavlink_message_t* msg, float *covariance) -{ - return _MAV_RETURN_float_array(msg, covariance, 21, 36); -} - -/** - * @brief Decode a att_pos_mocap message into a struct - * - * @param msg The message to decode - * @param att_pos_mocap C-struct to decode the message contents into - */ -static inline void mavlink_msg_att_pos_mocap_decode(const mavlink_message_t* msg, mavlink_att_pos_mocap_t* att_pos_mocap) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - att_pos_mocap->time_usec = mavlink_msg_att_pos_mocap_get_time_usec(msg); - mavlink_msg_att_pos_mocap_get_q(msg, att_pos_mocap->q); - att_pos_mocap->x = mavlink_msg_att_pos_mocap_get_x(msg); - att_pos_mocap->y = mavlink_msg_att_pos_mocap_get_y(msg); - att_pos_mocap->z = mavlink_msg_att_pos_mocap_get_z(msg); - mavlink_msg_att_pos_mocap_get_covariance(msg, att_pos_mocap->covariance); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN? msg->len : MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN; - memset(att_pos_mocap, 0, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN); - memcpy(att_pos_mocap, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_attitude.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_attitude.h deleted file mode 100644 index 21c1a9f1..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_attitude.h +++ /dev/null @@ -1,363 +0,0 @@ -#pragma once -// MESSAGE ATTITUDE PACKING - -#define MAVLINK_MSG_ID_ATTITUDE 30 - - -typedef struct __mavlink_attitude_t { - uint32_t time_boot_ms; /*< [ms] Timestamp (time since system boot).*/ - float roll; /*< [rad] Roll angle (-pi..+pi)*/ - float pitch; /*< [rad] Pitch angle (-pi..+pi)*/ - float yaw; /*< [rad] Yaw angle (-pi..+pi)*/ - float rollspeed; /*< [rad/s] Roll angular speed*/ - float pitchspeed; /*< [rad/s] Pitch angular speed*/ - float yawspeed; /*< [rad/s] Yaw angular speed*/ -} mavlink_attitude_t; - -#define MAVLINK_MSG_ID_ATTITUDE_LEN 28 -#define MAVLINK_MSG_ID_ATTITUDE_MIN_LEN 28 -#define MAVLINK_MSG_ID_30_LEN 28 -#define MAVLINK_MSG_ID_30_MIN_LEN 28 - -#define MAVLINK_MSG_ID_ATTITUDE_CRC 39 -#define MAVLINK_MSG_ID_30_CRC 39 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_ATTITUDE { \ - 30, \ - "ATTITUDE", \ - 7, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_attitude_t, time_boot_ms) }, \ - { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_attitude_t, roll) }, \ - { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_attitude_t, pitch) }, \ - { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_attitude_t, yaw) }, \ - { "rollspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_attitude_t, rollspeed) }, \ - { "pitchspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_attitude_t, pitchspeed) }, \ - { "yawspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_attitude_t, yawspeed) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_ATTITUDE { \ - "ATTITUDE", \ - 7, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_attitude_t, time_boot_ms) }, \ - { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_attitude_t, roll) }, \ - { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_attitude_t, pitch) }, \ - { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_attitude_t, yaw) }, \ - { "rollspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_attitude_t, rollspeed) }, \ - { "pitchspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_attitude_t, pitchspeed) }, \ - { "yawspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_attitude_t, yawspeed) }, \ - } \ -} -#endif - -/** - * @brief Pack a attitude message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param time_boot_ms [ms] Timestamp (time since system boot). - * @param roll [rad] Roll angle (-pi..+pi) - * @param pitch [rad] Pitch angle (-pi..+pi) - * @param yaw [rad] Yaw angle (-pi..+pi) - * @param rollspeed [rad/s] Roll angular speed - * @param pitchspeed [rad/s] Pitch angular speed - * @param yawspeed [rad/s] Yaw angular speed - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_attitude_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint32_t time_boot_ms, float roll, float pitch, float yaw, float rollspeed, float pitchspeed, float yawspeed) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_ATTITUDE_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, roll); - _mav_put_float(buf, 8, pitch); - _mav_put_float(buf, 12, yaw); - _mav_put_float(buf, 16, rollspeed); - _mav_put_float(buf, 20, pitchspeed); - _mav_put_float(buf, 24, yawspeed); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ATTITUDE_LEN); -#else - mavlink_attitude_t packet; - packet.time_boot_ms = time_boot_ms; - packet.roll = roll; - packet.pitch = pitch; - packet.yaw = yaw; - packet.rollspeed = rollspeed; - packet.pitchspeed = pitchspeed; - packet.yawspeed = yawspeed; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ATTITUDE_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_ATTITUDE; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ATTITUDE_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_LEN, MAVLINK_MSG_ID_ATTITUDE_CRC); -} - -/** - * @brief Pack a attitude message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_boot_ms [ms] Timestamp (time since system boot). - * @param roll [rad] Roll angle (-pi..+pi) - * @param pitch [rad] Pitch angle (-pi..+pi) - * @param yaw [rad] Yaw angle (-pi..+pi) - * @param rollspeed [rad/s] Roll angular speed - * @param pitchspeed [rad/s] Pitch angular speed - * @param yawspeed [rad/s] Yaw angular speed - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_attitude_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint32_t time_boot_ms,float roll,float pitch,float yaw,float rollspeed,float pitchspeed,float yawspeed) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_ATTITUDE_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, roll); - _mav_put_float(buf, 8, pitch); - _mav_put_float(buf, 12, yaw); - _mav_put_float(buf, 16, rollspeed); - _mav_put_float(buf, 20, pitchspeed); - _mav_put_float(buf, 24, yawspeed); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ATTITUDE_LEN); -#else - mavlink_attitude_t packet; - packet.time_boot_ms = time_boot_ms; - packet.roll = roll; - packet.pitch = pitch; - packet.yaw = yaw; - packet.rollspeed = rollspeed; - packet.pitchspeed = pitchspeed; - packet.yawspeed = yawspeed; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ATTITUDE_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_ATTITUDE; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ATTITUDE_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_LEN, MAVLINK_MSG_ID_ATTITUDE_CRC); -} - -/** - * @brief Encode a attitude struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param attitude C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_attitude_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_attitude_t* attitude) -{ - return mavlink_msg_attitude_pack(system_id, component_id, msg, attitude->time_boot_ms, attitude->roll, attitude->pitch, attitude->yaw, attitude->rollspeed, attitude->pitchspeed, attitude->yawspeed); -} - -/** - * @brief Encode a attitude struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param attitude C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_attitude_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_attitude_t* attitude) -{ - return mavlink_msg_attitude_pack_chan(system_id, component_id, chan, msg, attitude->time_boot_ms, attitude->roll, attitude->pitch, attitude->yaw, attitude->rollspeed, attitude->pitchspeed, attitude->yawspeed); -} - -/** - * @brief Send a attitude message - * @param chan MAVLink channel to send the message - * - * @param time_boot_ms [ms] Timestamp (time since system boot). - * @param roll [rad] Roll angle (-pi..+pi) - * @param pitch [rad] Pitch angle (-pi..+pi) - * @param yaw [rad] Yaw angle (-pi..+pi) - * @param rollspeed [rad/s] Roll angular speed - * @param pitchspeed [rad/s] Pitch angular speed - * @param yawspeed [rad/s] Yaw angular speed - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_attitude_send(mavlink_channel_t chan, uint32_t time_boot_ms, float roll, float pitch, float yaw, float rollspeed, float pitchspeed, float yawspeed) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_ATTITUDE_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, roll); - _mav_put_float(buf, 8, pitch); - _mav_put_float(buf, 12, yaw); - _mav_put_float(buf, 16, rollspeed); - _mav_put_float(buf, 20, pitchspeed); - _mav_put_float(buf, 24, yawspeed); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE, buf, MAVLINK_MSG_ID_ATTITUDE_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_LEN, MAVLINK_MSG_ID_ATTITUDE_CRC); -#else - mavlink_attitude_t packet; - packet.time_boot_ms = time_boot_ms; - packet.roll = roll; - packet.pitch = pitch; - packet.yaw = yaw; - packet.rollspeed = rollspeed; - packet.pitchspeed = pitchspeed; - packet.yawspeed = yawspeed; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE, (const char *)&packet, MAVLINK_MSG_ID_ATTITUDE_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_LEN, MAVLINK_MSG_ID_ATTITUDE_CRC); -#endif -} - -/** - * @brief Send a attitude message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_attitude_send_struct(mavlink_channel_t chan, const mavlink_attitude_t* attitude) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_attitude_send(chan, attitude->time_boot_ms, attitude->roll, attitude->pitch, attitude->yaw, attitude->rollspeed, attitude->pitchspeed, attitude->yawspeed); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE, (const char *)attitude, MAVLINK_MSG_ID_ATTITUDE_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_LEN, MAVLINK_MSG_ID_ATTITUDE_CRC); -#endif -} - -#if MAVLINK_MSG_ID_ATTITUDE_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_attitude_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, float roll, float pitch, float yaw, float rollspeed, float pitchspeed, float yawspeed) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, roll); - _mav_put_float(buf, 8, pitch); - _mav_put_float(buf, 12, yaw); - _mav_put_float(buf, 16, rollspeed); - _mav_put_float(buf, 20, pitchspeed); - _mav_put_float(buf, 24, yawspeed); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE, buf, MAVLINK_MSG_ID_ATTITUDE_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_LEN, MAVLINK_MSG_ID_ATTITUDE_CRC); -#else - mavlink_attitude_t *packet = (mavlink_attitude_t *)msgbuf; - packet->time_boot_ms = time_boot_ms; - packet->roll = roll; - packet->pitch = pitch; - packet->yaw = yaw; - packet->rollspeed = rollspeed; - packet->pitchspeed = pitchspeed; - packet->yawspeed = yawspeed; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE, (const char *)packet, MAVLINK_MSG_ID_ATTITUDE_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_LEN, MAVLINK_MSG_ID_ATTITUDE_CRC); -#endif -} -#endif - -#endif - -// MESSAGE ATTITUDE UNPACKING - - -/** - * @brief Get field time_boot_ms from attitude message - * - * @return [ms] Timestamp (time since system boot). - */ -static inline uint32_t mavlink_msg_attitude_get_time_boot_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field roll from attitude message - * - * @return [rad] Roll angle (-pi..+pi) - */ -static inline float mavlink_msg_attitude_get_roll(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 4); -} - -/** - * @brief Get field pitch from attitude message - * - * @return [rad] Pitch angle (-pi..+pi) - */ -static inline float mavlink_msg_attitude_get_pitch(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field yaw from attitude message - * - * @return [rad] Yaw angle (-pi..+pi) - */ -static inline float mavlink_msg_attitude_get_yaw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field rollspeed from attitude message - * - * @return [rad/s] Roll angular speed - */ -static inline float mavlink_msg_attitude_get_rollspeed(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field pitchspeed from attitude message - * - * @return [rad/s] Pitch angular speed - */ -static inline float mavlink_msg_attitude_get_pitchspeed(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Get field yawspeed from attitude message - * - * @return [rad/s] Yaw angular speed - */ -static inline float mavlink_msg_attitude_get_yawspeed(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Decode a attitude message into a struct - * - * @param msg The message to decode - * @param attitude C-struct to decode the message contents into - */ -static inline void mavlink_msg_attitude_decode(const mavlink_message_t* msg, mavlink_attitude_t* attitude) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - attitude->time_boot_ms = mavlink_msg_attitude_get_time_boot_ms(msg); - attitude->roll = mavlink_msg_attitude_get_roll(msg); - attitude->pitch = mavlink_msg_attitude_get_pitch(msg); - attitude->yaw = mavlink_msg_attitude_get_yaw(msg); - attitude->rollspeed = mavlink_msg_attitude_get_rollspeed(msg); - attitude->pitchspeed = mavlink_msg_attitude_get_pitchspeed(msg); - attitude->yawspeed = mavlink_msg_attitude_get_yawspeed(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_ATTITUDE_LEN? msg->len : MAVLINK_MSG_ID_ATTITUDE_LEN; - memset(attitude, 0, MAVLINK_MSG_ID_ATTITUDE_LEN); - memcpy(attitude, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_attitude_quaternion.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_attitude_quaternion.h deleted file mode 100644 index c22721d3..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_attitude_quaternion.h +++ /dev/null @@ -1,405 +0,0 @@ -#pragma once -// MESSAGE ATTITUDE_QUATERNION PACKING - -#define MAVLINK_MSG_ID_ATTITUDE_QUATERNION 31 - - -typedef struct __mavlink_attitude_quaternion_t { - uint32_t time_boot_ms; /*< [ms] Timestamp (time since system boot).*/ - float q1; /*< Quaternion component 1, w (1 in null-rotation)*/ - float q2; /*< Quaternion component 2, x (0 in null-rotation)*/ - float q3; /*< Quaternion component 3, y (0 in null-rotation)*/ - float q4; /*< Quaternion component 4, z (0 in null-rotation)*/ - float rollspeed; /*< [rad/s] Roll angular speed*/ - float pitchspeed; /*< [rad/s] Pitch angular speed*/ - float yawspeed; /*< [rad/s] Yaw angular speed*/ - float repr_offset_q[4]; /*< Rotation offset by which the attitude quaternion and angular speed vector should be rotated for user display (quaternion with [w, x, y, z] order, zero-rotation is [1, 0, 0, 0], send [0, 0, 0, 0] if field not supported). This field is intended for systems in which the reference attitude may change during flight. For example, tailsitters VTOLs rotate their reference attitude by 90 degrees between hover mode and fixed wing mode, thus repr_offset_q is equal to [1, 0, 0, 0] in hover mode and equal to [0.7071, 0, 0.7071, 0] in fixed wing mode.*/ -} mavlink_attitude_quaternion_t; - -#define MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN 48 -#define MAVLINK_MSG_ID_ATTITUDE_QUATERNION_MIN_LEN 32 -#define MAVLINK_MSG_ID_31_LEN 48 -#define MAVLINK_MSG_ID_31_MIN_LEN 32 - -#define MAVLINK_MSG_ID_ATTITUDE_QUATERNION_CRC 246 -#define MAVLINK_MSG_ID_31_CRC 246 - -#define MAVLINK_MSG_ATTITUDE_QUATERNION_FIELD_REPR_OFFSET_Q_LEN 4 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION { \ - 31, \ - "ATTITUDE_QUATERNION", \ - 9, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_attitude_quaternion_t, time_boot_ms) }, \ - { "q1", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_attitude_quaternion_t, q1) }, \ - { "q2", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_attitude_quaternion_t, q2) }, \ - { "q3", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_attitude_quaternion_t, q3) }, \ - { "q4", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_attitude_quaternion_t, q4) }, \ - { "rollspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_attitude_quaternion_t, rollspeed) }, \ - { "pitchspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_attitude_quaternion_t, pitchspeed) }, \ - { "yawspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_attitude_quaternion_t, yawspeed) }, \ - { "repr_offset_q", NULL, MAVLINK_TYPE_FLOAT, 4, 32, offsetof(mavlink_attitude_quaternion_t, repr_offset_q) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION { \ - "ATTITUDE_QUATERNION", \ - 9, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_attitude_quaternion_t, time_boot_ms) }, \ - { "q1", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_attitude_quaternion_t, q1) }, \ - { "q2", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_attitude_quaternion_t, q2) }, \ - { "q3", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_attitude_quaternion_t, q3) }, \ - { "q4", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_attitude_quaternion_t, q4) }, \ - { "rollspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_attitude_quaternion_t, rollspeed) }, \ - { "pitchspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_attitude_quaternion_t, pitchspeed) }, \ - { "yawspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_attitude_quaternion_t, yawspeed) }, \ - { "repr_offset_q", NULL, MAVLINK_TYPE_FLOAT, 4, 32, offsetof(mavlink_attitude_quaternion_t, repr_offset_q) }, \ - } \ -} -#endif - -/** - * @brief Pack a attitude_quaternion message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param time_boot_ms [ms] Timestamp (time since system boot). - * @param q1 Quaternion component 1, w (1 in null-rotation) - * @param q2 Quaternion component 2, x (0 in null-rotation) - * @param q3 Quaternion component 3, y (0 in null-rotation) - * @param q4 Quaternion component 4, z (0 in null-rotation) - * @param rollspeed [rad/s] Roll angular speed - * @param pitchspeed [rad/s] Pitch angular speed - * @param yawspeed [rad/s] Yaw angular speed - * @param repr_offset_q Rotation offset by which the attitude quaternion and angular speed vector should be rotated for user display (quaternion with [w, x, y, z] order, zero-rotation is [1, 0, 0, 0], send [0, 0, 0, 0] if field not supported). This field is intended for systems in which the reference attitude may change during flight. For example, tailsitters VTOLs rotate their reference attitude by 90 degrees between hover mode and fixed wing mode, thus repr_offset_q is equal to [1, 0, 0, 0] in hover mode and equal to [0.7071, 0, 0.7071, 0] in fixed wing mode. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_attitude_quaternion_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint32_t time_boot_ms, float q1, float q2, float q3, float q4, float rollspeed, float pitchspeed, float yawspeed, const float *repr_offset_q) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, q1); - _mav_put_float(buf, 8, q2); - _mav_put_float(buf, 12, q3); - _mav_put_float(buf, 16, q4); - _mav_put_float(buf, 20, rollspeed); - _mav_put_float(buf, 24, pitchspeed); - _mav_put_float(buf, 28, yawspeed); - _mav_put_float_array(buf, 32, repr_offset_q, 4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN); -#else - mavlink_attitude_quaternion_t packet; - packet.time_boot_ms = time_boot_ms; - packet.q1 = q1; - packet.q2 = q2; - packet.q3 = q3; - packet.q4 = q4; - packet.rollspeed = rollspeed; - packet.pitchspeed = pitchspeed; - packet.yawspeed = yawspeed; - mav_array_memcpy(packet.repr_offset_q, repr_offset_q, sizeof(float)*4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_ATTITUDE_QUATERNION; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_CRC); -} - -/** - * @brief Pack a attitude_quaternion message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_boot_ms [ms] Timestamp (time since system boot). - * @param q1 Quaternion component 1, w (1 in null-rotation) - * @param q2 Quaternion component 2, x (0 in null-rotation) - * @param q3 Quaternion component 3, y (0 in null-rotation) - * @param q4 Quaternion component 4, z (0 in null-rotation) - * @param rollspeed [rad/s] Roll angular speed - * @param pitchspeed [rad/s] Pitch angular speed - * @param yawspeed [rad/s] Yaw angular speed - * @param repr_offset_q Rotation offset by which the attitude quaternion and angular speed vector should be rotated for user display (quaternion with [w, x, y, z] order, zero-rotation is [1, 0, 0, 0], send [0, 0, 0, 0] if field not supported). This field is intended for systems in which the reference attitude may change during flight. For example, tailsitters VTOLs rotate their reference attitude by 90 degrees between hover mode and fixed wing mode, thus repr_offset_q is equal to [1, 0, 0, 0] in hover mode and equal to [0.7071, 0, 0.7071, 0] in fixed wing mode. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_attitude_quaternion_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint32_t time_boot_ms,float q1,float q2,float q3,float q4,float rollspeed,float pitchspeed,float yawspeed,const float *repr_offset_q) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, q1); - _mav_put_float(buf, 8, q2); - _mav_put_float(buf, 12, q3); - _mav_put_float(buf, 16, q4); - _mav_put_float(buf, 20, rollspeed); - _mav_put_float(buf, 24, pitchspeed); - _mav_put_float(buf, 28, yawspeed); - _mav_put_float_array(buf, 32, repr_offset_q, 4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN); -#else - mavlink_attitude_quaternion_t packet; - packet.time_boot_ms = time_boot_ms; - packet.q1 = q1; - packet.q2 = q2; - packet.q3 = q3; - packet.q4 = q4; - packet.rollspeed = rollspeed; - packet.pitchspeed = pitchspeed; - packet.yawspeed = yawspeed; - mav_array_memcpy(packet.repr_offset_q, repr_offset_q, sizeof(float)*4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_ATTITUDE_QUATERNION; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_CRC); -} - -/** - * @brief Encode a attitude_quaternion struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param attitude_quaternion C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_attitude_quaternion_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_attitude_quaternion_t* attitude_quaternion) -{ - return mavlink_msg_attitude_quaternion_pack(system_id, component_id, msg, attitude_quaternion->time_boot_ms, attitude_quaternion->q1, attitude_quaternion->q2, attitude_quaternion->q3, attitude_quaternion->q4, attitude_quaternion->rollspeed, attitude_quaternion->pitchspeed, attitude_quaternion->yawspeed, attitude_quaternion->repr_offset_q); -} - -/** - * @brief Encode a attitude_quaternion struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param attitude_quaternion C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_attitude_quaternion_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_attitude_quaternion_t* attitude_quaternion) -{ - return mavlink_msg_attitude_quaternion_pack_chan(system_id, component_id, chan, msg, attitude_quaternion->time_boot_ms, attitude_quaternion->q1, attitude_quaternion->q2, attitude_quaternion->q3, attitude_quaternion->q4, attitude_quaternion->rollspeed, attitude_quaternion->pitchspeed, attitude_quaternion->yawspeed, attitude_quaternion->repr_offset_q); -} - -/** - * @brief Send a attitude_quaternion message - * @param chan MAVLink channel to send the message - * - * @param time_boot_ms [ms] Timestamp (time since system boot). - * @param q1 Quaternion component 1, w (1 in null-rotation) - * @param q2 Quaternion component 2, x (0 in null-rotation) - * @param q3 Quaternion component 3, y (0 in null-rotation) - * @param q4 Quaternion component 4, z (0 in null-rotation) - * @param rollspeed [rad/s] Roll angular speed - * @param pitchspeed [rad/s] Pitch angular speed - * @param yawspeed [rad/s] Yaw angular speed - * @param repr_offset_q Rotation offset by which the attitude quaternion and angular speed vector should be rotated for user display (quaternion with [w, x, y, z] order, zero-rotation is [1, 0, 0, 0], send [0, 0, 0, 0] if field not supported). This field is intended for systems in which the reference attitude may change during flight. For example, tailsitters VTOLs rotate their reference attitude by 90 degrees between hover mode and fixed wing mode, thus repr_offset_q is equal to [1, 0, 0, 0] in hover mode and equal to [0.7071, 0, 0.7071, 0] in fixed wing mode. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_attitude_quaternion_send(mavlink_channel_t chan, uint32_t time_boot_ms, float q1, float q2, float q3, float q4, float rollspeed, float pitchspeed, float yawspeed, const float *repr_offset_q) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, q1); - _mav_put_float(buf, 8, q2); - _mav_put_float(buf, 12, q3); - _mav_put_float(buf, 16, q4); - _mav_put_float(buf, 20, rollspeed); - _mav_put_float(buf, 24, pitchspeed); - _mav_put_float(buf, 28, yawspeed); - _mav_put_float_array(buf, 32, repr_offset_q, 4); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION, buf, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_CRC); -#else - mavlink_attitude_quaternion_t packet; - packet.time_boot_ms = time_boot_ms; - packet.q1 = q1; - packet.q2 = q2; - packet.q3 = q3; - packet.q4 = q4; - packet.rollspeed = rollspeed; - packet.pitchspeed = pitchspeed; - packet.yawspeed = yawspeed; - mav_array_memcpy(packet.repr_offset_q, repr_offset_q, sizeof(float)*4); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION, (const char *)&packet, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_CRC); -#endif -} - -/** - * @brief Send a attitude_quaternion message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_attitude_quaternion_send_struct(mavlink_channel_t chan, const mavlink_attitude_quaternion_t* attitude_quaternion) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_attitude_quaternion_send(chan, attitude_quaternion->time_boot_ms, attitude_quaternion->q1, attitude_quaternion->q2, attitude_quaternion->q3, attitude_quaternion->q4, attitude_quaternion->rollspeed, attitude_quaternion->pitchspeed, attitude_quaternion->yawspeed, attitude_quaternion->repr_offset_q); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION, (const char *)attitude_quaternion, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_CRC); -#endif -} - -#if MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_attitude_quaternion_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, float q1, float q2, float q3, float q4, float rollspeed, float pitchspeed, float yawspeed, const float *repr_offset_q) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, q1); - _mav_put_float(buf, 8, q2); - _mav_put_float(buf, 12, q3); - _mav_put_float(buf, 16, q4); - _mav_put_float(buf, 20, rollspeed); - _mav_put_float(buf, 24, pitchspeed); - _mav_put_float(buf, 28, yawspeed); - _mav_put_float_array(buf, 32, repr_offset_q, 4); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION, buf, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_CRC); -#else - mavlink_attitude_quaternion_t *packet = (mavlink_attitude_quaternion_t *)msgbuf; - packet->time_boot_ms = time_boot_ms; - packet->q1 = q1; - packet->q2 = q2; - packet->q3 = q3; - packet->q4 = q4; - packet->rollspeed = rollspeed; - packet->pitchspeed = pitchspeed; - packet->yawspeed = yawspeed; - mav_array_memcpy(packet->repr_offset_q, repr_offset_q, sizeof(float)*4); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION, (const char *)packet, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_CRC); -#endif -} -#endif - -#endif - -// MESSAGE ATTITUDE_QUATERNION UNPACKING - - -/** - * @brief Get field time_boot_ms from attitude_quaternion message - * - * @return [ms] Timestamp (time since system boot). - */ -static inline uint32_t mavlink_msg_attitude_quaternion_get_time_boot_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field q1 from attitude_quaternion message - * - * @return Quaternion component 1, w (1 in null-rotation) - */ -static inline float mavlink_msg_attitude_quaternion_get_q1(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 4); -} - -/** - * @brief Get field q2 from attitude_quaternion message - * - * @return Quaternion component 2, x (0 in null-rotation) - */ -static inline float mavlink_msg_attitude_quaternion_get_q2(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field q3 from attitude_quaternion message - * - * @return Quaternion component 3, y (0 in null-rotation) - */ -static inline float mavlink_msg_attitude_quaternion_get_q3(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field q4 from attitude_quaternion message - * - * @return Quaternion component 4, z (0 in null-rotation) - */ -static inline float mavlink_msg_attitude_quaternion_get_q4(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field rollspeed from attitude_quaternion message - * - * @return [rad/s] Roll angular speed - */ -static inline float mavlink_msg_attitude_quaternion_get_rollspeed(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Get field pitchspeed from attitude_quaternion message - * - * @return [rad/s] Pitch angular speed - */ -static inline float mavlink_msg_attitude_quaternion_get_pitchspeed(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Get field yawspeed from attitude_quaternion message - * - * @return [rad/s] Yaw angular speed - */ -static inline float mavlink_msg_attitude_quaternion_get_yawspeed(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 28); -} - -/** - * @brief Get field repr_offset_q from attitude_quaternion message - * - * @return Rotation offset by which the attitude quaternion and angular speed vector should be rotated for user display (quaternion with [w, x, y, z] order, zero-rotation is [1, 0, 0, 0], send [0, 0, 0, 0] if field not supported). This field is intended for systems in which the reference attitude may change during flight. For example, tailsitters VTOLs rotate their reference attitude by 90 degrees between hover mode and fixed wing mode, thus repr_offset_q is equal to [1, 0, 0, 0] in hover mode and equal to [0.7071, 0, 0.7071, 0] in fixed wing mode. - */ -static inline uint16_t mavlink_msg_attitude_quaternion_get_repr_offset_q(const mavlink_message_t* msg, float *repr_offset_q) -{ - return _MAV_RETURN_float_array(msg, repr_offset_q, 4, 32); -} - -/** - * @brief Decode a attitude_quaternion message into a struct - * - * @param msg The message to decode - * @param attitude_quaternion C-struct to decode the message contents into - */ -static inline void mavlink_msg_attitude_quaternion_decode(const mavlink_message_t* msg, mavlink_attitude_quaternion_t* attitude_quaternion) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - attitude_quaternion->time_boot_ms = mavlink_msg_attitude_quaternion_get_time_boot_ms(msg); - attitude_quaternion->q1 = mavlink_msg_attitude_quaternion_get_q1(msg); - attitude_quaternion->q2 = mavlink_msg_attitude_quaternion_get_q2(msg); - attitude_quaternion->q3 = mavlink_msg_attitude_quaternion_get_q3(msg); - attitude_quaternion->q4 = mavlink_msg_attitude_quaternion_get_q4(msg); - attitude_quaternion->rollspeed = mavlink_msg_attitude_quaternion_get_rollspeed(msg); - attitude_quaternion->pitchspeed = mavlink_msg_attitude_quaternion_get_pitchspeed(msg); - attitude_quaternion->yawspeed = mavlink_msg_attitude_quaternion_get_yawspeed(msg); - mavlink_msg_attitude_quaternion_get_repr_offset_q(msg, attitude_quaternion->repr_offset_q); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN? msg->len : MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN; - memset(attitude_quaternion, 0, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN); - memcpy(attitude_quaternion, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_attitude_quaternion_cov.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_attitude_quaternion_cov.h deleted file mode 100644 index 766f070a..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_attitude_quaternion_cov.h +++ /dev/null @@ -1,331 +0,0 @@ -#pragma once -// MESSAGE ATTITUDE_QUATERNION_COV PACKING - -#define MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV 61 - - -typedef struct __mavlink_attitude_quaternion_cov_t { - uint64_t time_usec; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/ - float q[4]; /*< Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation)*/ - float rollspeed; /*< [rad/s] Roll angular speed*/ - float pitchspeed; /*< [rad/s] Pitch angular speed*/ - float yawspeed; /*< [rad/s] Yaw angular speed*/ - float covariance[9]; /*< Row-major representation of a 3x3 attitude covariance matrix (states: roll, pitch, yaw; first three entries are the first ROW, next three entries are the second row, etc.). If unknown, assign NaN value to first element in the array.*/ -} mavlink_attitude_quaternion_cov_t; - -#define MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN 72 -#define MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_MIN_LEN 72 -#define MAVLINK_MSG_ID_61_LEN 72 -#define MAVLINK_MSG_ID_61_MIN_LEN 72 - -#define MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_CRC 167 -#define MAVLINK_MSG_ID_61_CRC 167 - -#define MAVLINK_MSG_ATTITUDE_QUATERNION_COV_FIELD_Q_LEN 4 -#define MAVLINK_MSG_ATTITUDE_QUATERNION_COV_FIELD_COVARIANCE_LEN 9 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION_COV { \ - 61, \ - "ATTITUDE_QUATERNION_COV", \ - 6, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_attitude_quaternion_cov_t, time_usec) }, \ - { "q", NULL, MAVLINK_TYPE_FLOAT, 4, 8, offsetof(mavlink_attitude_quaternion_cov_t, q) }, \ - { "rollspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_attitude_quaternion_cov_t, rollspeed) }, \ - { "pitchspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_attitude_quaternion_cov_t, pitchspeed) }, \ - { "yawspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_attitude_quaternion_cov_t, yawspeed) }, \ - { "covariance", NULL, MAVLINK_TYPE_FLOAT, 9, 36, offsetof(mavlink_attitude_quaternion_cov_t, covariance) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION_COV { \ - "ATTITUDE_QUATERNION_COV", \ - 6, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_attitude_quaternion_cov_t, time_usec) }, \ - { "q", NULL, MAVLINK_TYPE_FLOAT, 4, 8, offsetof(mavlink_attitude_quaternion_cov_t, q) }, \ - { "rollspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_attitude_quaternion_cov_t, rollspeed) }, \ - { "pitchspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_attitude_quaternion_cov_t, pitchspeed) }, \ - { "yawspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_attitude_quaternion_cov_t, yawspeed) }, \ - { "covariance", NULL, MAVLINK_TYPE_FLOAT, 9, 36, offsetof(mavlink_attitude_quaternion_cov_t, covariance) }, \ - } \ -} -#endif - -/** - * @brief Pack a attitude_quaternion_cov message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @param q Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation) - * @param rollspeed [rad/s] Roll angular speed - * @param pitchspeed [rad/s] Pitch angular speed - * @param yawspeed [rad/s] Yaw angular speed - * @param covariance Row-major representation of a 3x3 attitude covariance matrix (states: roll, pitch, yaw; first three entries are the first ROW, next three entries are the second row, etc.). If unknown, assign NaN value to first element in the array. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_attitude_quaternion_cov_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint64_t time_usec, const float *q, float rollspeed, float pitchspeed, float yawspeed, const float *covariance) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 24, rollspeed); - _mav_put_float(buf, 28, pitchspeed); - _mav_put_float(buf, 32, yawspeed); - _mav_put_float_array(buf, 8, q, 4); - _mav_put_float_array(buf, 36, covariance, 9); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN); -#else - mavlink_attitude_quaternion_cov_t packet; - packet.time_usec = time_usec; - packet.rollspeed = rollspeed; - packet.pitchspeed = pitchspeed; - packet.yawspeed = yawspeed; - mav_array_memcpy(packet.q, q, sizeof(float)*4); - mav_array_memcpy(packet.covariance, covariance, sizeof(float)*9); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_CRC); -} - -/** - * @brief Pack a attitude_quaternion_cov message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @param q Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation) - * @param rollspeed [rad/s] Roll angular speed - * @param pitchspeed [rad/s] Pitch angular speed - * @param yawspeed [rad/s] Yaw angular speed - * @param covariance Row-major representation of a 3x3 attitude covariance matrix (states: roll, pitch, yaw; first three entries are the first ROW, next three entries are the second row, etc.). If unknown, assign NaN value to first element in the array. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_attitude_quaternion_cov_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint64_t time_usec,const float *q,float rollspeed,float pitchspeed,float yawspeed,const float *covariance) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 24, rollspeed); - _mav_put_float(buf, 28, pitchspeed); - _mav_put_float(buf, 32, yawspeed); - _mav_put_float_array(buf, 8, q, 4); - _mav_put_float_array(buf, 36, covariance, 9); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN); -#else - mavlink_attitude_quaternion_cov_t packet; - packet.time_usec = time_usec; - packet.rollspeed = rollspeed; - packet.pitchspeed = pitchspeed; - packet.yawspeed = yawspeed; - mav_array_memcpy(packet.q, q, sizeof(float)*4); - mav_array_memcpy(packet.covariance, covariance, sizeof(float)*9); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_CRC); -} - -/** - * @brief Encode a attitude_quaternion_cov struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param attitude_quaternion_cov C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_attitude_quaternion_cov_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_attitude_quaternion_cov_t* attitude_quaternion_cov) -{ - return mavlink_msg_attitude_quaternion_cov_pack(system_id, component_id, msg, attitude_quaternion_cov->time_usec, attitude_quaternion_cov->q, attitude_quaternion_cov->rollspeed, attitude_quaternion_cov->pitchspeed, attitude_quaternion_cov->yawspeed, attitude_quaternion_cov->covariance); -} - -/** - * @brief Encode a attitude_quaternion_cov struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param attitude_quaternion_cov C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_attitude_quaternion_cov_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_attitude_quaternion_cov_t* attitude_quaternion_cov) -{ - return mavlink_msg_attitude_quaternion_cov_pack_chan(system_id, component_id, chan, msg, attitude_quaternion_cov->time_usec, attitude_quaternion_cov->q, attitude_quaternion_cov->rollspeed, attitude_quaternion_cov->pitchspeed, attitude_quaternion_cov->yawspeed, attitude_quaternion_cov->covariance); -} - -/** - * @brief Send a attitude_quaternion_cov message - * @param chan MAVLink channel to send the message - * - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @param q Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation) - * @param rollspeed [rad/s] Roll angular speed - * @param pitchspeed [rad/s] Pitch angular speed - * @param yawspeed [rad/s] Yaw angular speed - * @param covariance Row-major representation of a 3x3 attitude covariance matrix (states: roll, pitch, yaw; first three entries are the first ROW, next three entries are the second row, etc.). If unknown, assign NaN value to first element in the array. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_attitude_quaternion_cov_send(mavlink_channel_t chan, uint64_t time_usec, const float *q, float rollspeed, float pitchspeed, float yawspeed, const float *covariance) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 24, rollspeed); - _mav_put_float(buf, 28, pitchspeed); - _mav_put_float(buf, 32, yawspeed); - _mav_put_float_array(buf, 8, q, 4); - _mav_put_float_array(buf, 36, covariance, 9); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV, buf, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_CRC); -#else - mavlink_attitude_quaternion_cov_t packet; - packet.time_usec = time_usec; - packet.rollspeed = rollspeed; - packet.pitchspeed = pitchspeed; - packet.yawspeed = yawspeed; - mav_array_memcpy(packet.q, q, sizeof(float)*4); - mav_array_memcpy(packet.covariance, covariance, sizeof(float)*9); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV, (const char *)&packet, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_CRC); -#endif -} - -/** - * @brief Send a attitude_quaternion_cov message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_attitude_quaternion_cov_send_struct(mavlink_channel_t chan, const mavlink_attitude_quaternion_cov_t* attitude_quaternion_cov) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_attitude_quaternion_cov_send(chan, attitude_quaternion_cov->time_usec, attitude_quaternion_cov->q, attitude_quaternion_cov->rollspeed, attitude_quaternion_cov->pitchspeed, attitude_quaternion_cov->yawspeed, attitude_quaternion_cov->covariance); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV, (const char *)attitude_quaternion_cov, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_CRC); -#endif -} - -#if MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_attitude_quaternion_cov_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, const float *q, float rollspeed, float pitchspeed, float yawspeed, const float *covariance) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 24, rollspeed); - _mav_put_float(buf, 28, pitchspeed); - _mav_put_float(buf, 32, yawspeed); - _mav_put_float_array(buf, 8, q, 4); - _mav_put_float_array(buf, 36, covariance, 9); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV, buf, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_CRC); -#else - mavlink_attitude_quaternion_cov_t *packet = (mavlink_attitude_quaternion_cov_t *)msgbuf; - packet->time_usec = time_usec; - packet->rollspeed = rollspeed; - packet->pitchspeed = pitchspeed; - packet->yawspeed = yawspeed; - mav_array_memcpy(packet->q, q, sizeof(float)*4); - mav_array_memcpy(packet->covariance, covariance, sizeof(float)*9); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV, (const char *)packet, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_CRC); -#endif -} -#endif - -#endif - -// MESSAGE ATTITUDE_QUATERNION_COV UNPACKING - - -/** - * @brief Get field time_usec from attitude_quaternion_cov message - * - * @return [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - */ -static inline uint64_t mavlink_msg_attitude_quaternion_cov_get_time_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field q from attitude_quaternion_cov message - * - * @return Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation) - */ -static inline uint16_t mavlink_msg_attitude_quaternion_cov_get_q(const mavlink_message_t* msg, float *q) -{ - return _MAV_RETURN_float_array(msg, q, 4, 8); -} - -/** - * @brief Get field rollspeed from attitude_quaternion_cov message - * - * @return [rad/s] Roll angular speed - */ -static inline float mavlink_msg_attitude_quaternion_cov_get_rollspeed(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Get field pitchspeed from attitude_quaternion_cov message - * - * @return [rad/s] Pitch angular speed - */ -static inline float mavlink_msg_attitude_quaternion_cov_get_pitchspeed(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 28); -} - -/** - * @brief Get field yawspeed from attitude_quaternion_cov message - * - * @return [rad/s] Yaw angular speed - */ -static inline float mavlink_msg_attitude_quaternion_cov_get_yawspeed(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 32); -} - -/** - * @brief Get field covariance from attitude_quaternion_cov message - * - * @return Row-major representation of a 3x3 attitude covariance matrix (states: roll, pitch, yaw; first three entries are the first ROW, next three entries are the second row, etc.). If unknown, assign NaN value to first element in the array. - */ -static inline uint16_t mavlink_msg_attitude_quaternion_cov_get_covariance(const mavlink_message_t* msg, float *covariance) -{ - return _MAV_RETURN_float_array(msg, covariance, 9, 36); -} - -/** - * @brief Decode a attitude_quaternion_cov message into a struct - * - * @param msg The message to decode - * @param attitude_quaternion_cov C-struct to decode the message contents into - */ -static inline void mavlink_msg_attitude_quaternion_cov_decode(const mavlink_message_t* msg, mavlink_attitude_quaternion_cov_t* attitude_quaternion_cov) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - attitude_quaternion_cov->time_usec = mavlink_msg_attitude_quaternion_cov_get_time_usec(msg); - mavlink_msg_attitude_quaternion_cov_get_q(msg, attitude_quaternion_cov->q); - attitude_quaternion_cov->rollspeed = mavlink_msg_attitude_quaternion_cov_get_rollspeed(msg); - attitude_quaternion_cov->pitchspeed = mavlink_msg_attitude_quaternion_cov_get_pitchspeed(msg); - attitude_quaternion_cov->yawspeed = mavlink_msg_attitude_quaternion_cov_get_yawspeed(msg); - mavlink_msg_attitude_quaternion_cov_get_covariance(msg, attitude_quaternion_cov->covariance); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN? msg->len : MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN; - memset(attitude_quaternion_cov, 0, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN); - memcpy(attitude_quaternion_cov, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_attitude_target.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_attitude_target.h deleted file mode 100644 index b67c07c8..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_attitude_target.h +++ /dev/null @@ -1,355 +0,0 @@ -#pragma once -// MESSAGE ATTITUDE_TARGET PACKING - -#define MAVLINK_MSG_ID_ATTITUDE_TARGET 83 - - -typedef struct __mavlink_attitude_target_t { - uint32_t time_boot_ms; /*< [ms] Timestamp (time since system boot).*/ - float q[4]; /*< Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0)*/ - float body_roll_rate; /*< [rad/s] Body roll rate*/ - float body_pitch_rate; /*< [rad/s] Body pitch rate*/ - float body_yaw_rate; /*< [rad/s] Body yaw rate*/ - float thrust; /*< Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust)*/ - uint8_t type_mask; /*< Bitmap to indicate which dimensions should be ignored by the vehicle.*/ -} mavlink_attitude_target_t; - -#define MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN 37 -#define MAVLINK_MSG_ID_ATTITUDE_TARGET_MIN_LEN 37 -#define MAVLINK_MSG_ID_83_LEN 37 -#define MAVLINK_MSG_ID_83_MIN_LEN 37 - -#define MAVLINK_MSG_ID_ATTITUDE_TARGET_CRC 22 -#define MAVLINK_MSG_ID_83_CRC 22 - -#define MAVLINK_MSG_ATTITUDE_TARGET_FIELD_Q_LEN 4 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_ATTITUDE_TARGET { \ - 83, \ - "ATTITUDE_TARGET", \ - 7, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_attitude_target_t, time_boot_ms) }, \ - { "type_mask", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_attitude_target_t, type_mask) }, \ - { "q", NULL, MAVLINK_TYPE_FLOAT, 4, 4, offsetof(mavlink_attitude_target_t, q) }, \ - { "body_roll_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_attitude_target_t, body_roll_rate) }, \ - { "body_pitch_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_attitude_target_t, body_pitch_rate) }, \ - { "body_yaw_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_attitude_target_t, body_yaw_rate) }, \ - { "thrust", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_attitude_target_t, thrust) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_ATTITUDE_TARGET { \ - "ATTITUDE_TARGET", \ - 7, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_attitude_target_t, time_boot_ms) }, \ - { "type_mask", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_attitude_target_t, type_mask) }, \ - { "q", NULL, MAVLINK_TYPE_FLOAT, 4, 4, offsetof(mavlink_attitude_target_t, q) }, \ - { "body_roll_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_attitude_target_t, body_roll_rate) }, \ - { "body_pitch_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_attitude_target_t, body_pitch_rate) }, \ - { "body_yaw_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_attitude_target_t, body_yaw_rate) }, \ - { "thrust", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_attitude_target_t, thrust) }, \ - } \ -} -#endif - -/** - * @brief Pack a attitude_target message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param time_boot_ms [ms] Timestamp (time since system boot). - * @param type_mask Bitmap to indicate which dimensions should be ignored by the vehicle. - * @param q Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) - * @param body_roll_rate [rad/s] Body roll rate - * @param body_pitch_rate [rad/s] Body pitch rate - * @param body_yaw_rate [rad/s] Body yaw rate - * @param thrust Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_attitude_target_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint32_t time_boot_ms, uint8_t type_mask, const float *q, float body_roll_rate, float body_pitch_rate, float body_yaw_rate, float thrust) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 20, body_roll_rate); - _mav_put_float(buf, 24, body_pitch_rate); - _mav_put_float(buf, 28, body_yaw_rate); - _mav_put_float(buf, 32, thrust); - _mav_put_uint8_t(buf, 36, type_mask); - _mav_put_float_array(buf, 4, q, 4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN); -#else - mavlink_attitude_target_t packet; - packet.time_boot_ms = time_boot_ms; - packet.body_roll_rate = body_roll_rate; - packet.body_pitch_rate = body_pitch_rate; - packet.body_yaw_rate = body_yaw_rate; - packet.thrust = thrust; - packet.type_mask = type_mask; - mav_array_memcpy(packet.q, q, sizeof(float)*4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_ATTITUDE_TARGET; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ATTITUDE_TARGET_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN, MAVLINK_MSG_ID_ATTITUDE_TARGET_CRC); -} - -/** - * @brief Pack a attitude_target message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_boot_ms [ms] Timestamp (time since system boot). - * @param type_mask Bitmap to indicate which dimensions should be ignored by the vehicle. - * @param q Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) - * @param body_roll_rate [rad/s] Body roll rate - * @param body_pitch_rate [rad/s] Body pitch rate - * @param body_yaw_rate [rad/s] Body yaw rate - * @param thrust Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_attitude_target_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint32_t time_boot_ms,uint8_t type_mask,const float *q,float body_roll_rate,float body_pitch_rate,float body_yaw_rate,float thrust) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 20, body_roll_rate); - _mav_put_float(buf, 24, body_pitch_rate); - _mav_put_float(buf, 28, body_yaw_rate); - _mav_put_float(buf, 32, thrust); - _mav_put_uint8_t(buf, 36, type_mask); - _mav_put_float_array(buf, 4, q, 4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN); -#else - mavlink_attitude_target_t packet; - packet.time_boot_ms = time_boot_ms; - packet.body_roll_rate = body_roll_rate; - packet.body_pitch_rate = body_pitch_rate; - packet.body_yaw_rate = body_yaw_rate; - packet.thrust = thrust; - packet.type_mask = type_mask; - mav_array_memcpy(packet.q, q, sizeof(float)*4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_ATTITUDE_TARGET; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ATTITUDE_TARGET_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN, MAVLINK_MSG_ID_ATTITUDE_TARGET_CRC); -} - -/** - * @brief Encode a attitude_target struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param attitude_target C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_attitude_target_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_attitude_target_t* attitude_target) -{ - return mavlink_msg_attitude_target_pack(system_id, component_id, msg, attitude_target->time_boot_ms, attitude_target->type_mask, attitude_target->q, attitude_target->body_roll_rate, attitude_target->body_pitch_rate, attitude_target->body_yaw_rate, attitude_target->thrust); -} - -/** - * @brief Encode a attitude_target struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param attitude_target C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_attitude_target_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_attitude_target_t* attitude_target) -{ - return mavlink_msg_attitude_target_pack_chan(system_id, component_id, chan, msg, attitude_target->time_boot_ms, attitude_target->type_mask, attitude_target->q, attitude_target->body_roll_rate, attitude_target->body_pitch_rate, attitude_target->body_yaw_rate, attitude_target->thrust); -} - -/** - * @brief Send a attitude_target message - * @param chan MAVLink channel to send the message - * - * @param time_boot_ms [ms] Timestamp (time since system boot). - * @param type_mask Bitmap to indicate which dimensions should be ignored by the vehicle. - * @param q Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) - * @param body_roll_rate [rad/s] Body roll rate - * @param body_pitch_rate [rad/s] Body pitch rate - * @param body_yaw_rate [rad/s] Body yaw rate - * @param thrust Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust) - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_attitude_target_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t type_mask, const float *q, float body_roll_rate, float body_pitch_rate, float body_yaw_rate, float thrust) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 20, body_roll_rate); - _mav_put_float(buf, 24, body_pitch_rate); - _mav_put_float(buf, 28, body_yaw_rate); - _mav_put_float(buf, 32, thrust); - _mav_put_uint8_t(buf, 36, type_mask); - _mav_put_float_array(buf, 4, q, 4); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_TARGET, buf, MAVLINK_MSG_ID_ATTITUDE_TARGET_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN, MAVLINK_MSG_ID_ATTITUDE_TARGET_CRC); -#else - mavlink_attitude_target_t packet; - packet.time_boot_ms = time_boot_ms; - packet.body_roll_rate = body_roll_rate; - packet.body_pitch_rate = body_pitch_rate; - packet.body_yaw_rate = body_yaw_rate; - packet.thrust = thrust; - packet.type_mask = type_mask; - mav_array_memcpy(packet.q, q, sizeof(float)*4); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_TARGET, (const char *)&packet, MAVLINK_MSG_ID_ATTITUDE_TARGET_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN, MAVLINK_MSG_ID_ATTITUDE_TARGET_CRC); -#endif -} - -/** - * @brief Send a attitude_target message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_attitude_target_send_struct(mavlink_channel_t chan, const mavlink_attitude_target_t* attitude_target) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_attitude_target_send(chan, attitude_target->time_boot_ms, attitude_target->type_mask, attitude_target->q, attitude_target->body_roll_rate, attitude_target->body_pitch_rate, attitude_target->body_yaw_rate, attitude_target->thrust); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_TARGET, (const char *)attitude_target, MAVLINK_MSG_ID_ATTITUDE_TARGET_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN, MAVLINK_MSG_ID_ATTITUDE_TARGET_CRC); -#endif -} - -#if MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_attitude_target_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t type_mask, const float *q, float body_roll_rate, float body_pitch_rate, float body_yaw_rate, float thrust) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 20, body_roll_rate); - _mav_put_float(buf, 24, body_pitch_rate); - _mav_put_float(buf, 28, body_yaw_rate); - _mav_put_float(buf, 32, thrust); - _mav_put_uint8_t(buf, 36, type_mask); - _mav_put_float_array(buf, 4, q, 4); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_TARGET, buf, MAVLINK_MSG_ID_ATTITUDE_TARGET_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN, MAVLINK_MSG_ID_ATTITUDE_TARGET_CRC); -#else - mavlink_attitude_target_t *packet = (mavlink_attitude_target_t *)msgbuf; - packet->time_boot_ms = time_boot_ms; - packet->body_roll_rate = body_roll_rate; - packet->body_pitch_rate = body_pitch_rate; - packet->body_yaw_rate = body_yaw_rate; - packet->thrust = thrust; - packet->type_mask = type_mask; - mav_array_memcpy(packet->q, q, sizeof(float)*4); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_TARGET, (const char *)packet, MAVLINK_MSG_ID_ATTITUDE_TARGET_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN, MAVLINK_MSG_ID_ATTITUDE_TARGET_CRC); -#endif -} -#endif - -#endif - -// MESSAGE ATTITUDE_TARGET UNPACKING - - -/** - * @brief Get field time_boot_ms from attitude_target message - * - * @return [ms] Timestamp (time since system boot). - */ -static inline uint32_t mavlink_msg_attitude_target_get_time_boot_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field type_mask from attitude_target message - * - * @return Bitmap to indicate which dimensions should be ignored by the vehicle. - */ -static inline uint8_t mavlink_msg_attitude_target_get_type_mask(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 36); -} - -/** - * @brief Get field q from attitude_target message - * - * @return Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) - */ -static inline uint16_t mavlink_msg_attitude_target_get_q(const mavlink_message_t* msg, float *q) -{ - return _MAV_RETURN_float_array(msg, q, 4, 4); -} - -/** - * @brief Get field body_roll_rate from attitude_target message - * - * @return [rad/s] Body roll rate - */ -static inline float mavlink_msg_attitude_target_get_body_roll_rate(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Get field body_pitch_rate from attitude_target message - * - * @return [rad/s] Body pitch rate - */ -static inline float mavlink_msg_attitude_target_get_body_pitch_rate(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Get field body_yaw_rate from attitude_target message - * - * @return [rad/s] Body yaw rate - */ -static inline float mavlink_msg_attitude_target_get_body_yaw_rate(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 28); -} - -/** - * @brief Get field thrust from attitude_target message - * - * @return Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust) - */ -static inline float mavlink_msg_attitude_target_get_thrust(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 32); -} - -/** - * @brief Decode a attitude_target message into a struct - * - * @param msg The message to decode - * @param attitude_target C-struct to decode the message contents into - */ -static inline void mavlink_msg_attitude_target_decode(const mavlink_message_t* msg, mavlink_attitude_target_t* attitude_target) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - attitude_target->time_boot_ms = mavlink_msg_attitude_target_get_time_boot_ms(msg); - mavlink_msg_attitude_target_get_q(msg, attitude_target->q); - attitude_target->body_roll_rate = mavlink_msg_attitude_target_get_body_roll_rate(msg); - attitude_target->body_pitch_rate = mavlink_msg_attitude_target_get_body_pitch_rate(msg); - attitude_target->body_yaw_rate = mavlink_msg_attitude_target_get_body_yaw_rate(msg); - attitude_target->thrust = mavlink_msg_attitude_target_get_thrust(msg); - attitude_target->type_mask = mavlink_msg_attitude_target_get_type_mask(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN? msg->len : MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN; - memset(attitude_target, 0, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN); - memcpy(attitude_target, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_auth_key.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_auth_key.h deleted file mode 100644 index 9dd7007f..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_auth_key.h +++ /dev/null @@ -1,213 +0,0 @@ -#pragma once -// MESSAGE AUTH_KEY PACKING - -#define MAVLINK_MSG_ID_AUTH_KEY 7 - - -typedef struct __mavlink_auth_key_t { - char key[32]; /*< key*/ -} mavlink_auth_key_t; - -#define MAVLINK_MSG_ID_AUTH_KEY_LEN 32 -#define MAVLINK_MSG_ID_AUTH_KEY_MIN_LEN 32 -#define MAVLINK_MSG_ID_7_LEN 32 -#define MAVLINK_MSG_ID_7_MIN_LEN 32 - -#define MAVLINK_MSG_ID_AUTH_KEY_CRC 119 -#define MAVLINK_MSG_ID_7_CRC 119 - -#define MAVLINK_MSG_AUTH_KEY_FIELD_KEY_LEN 32 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_AUTH_KEY { \ - 7, \ - "AUTH_KEY", \ - 1, \ - { { "key", NULL, MAVLINK_TYPE_CHAR, 32, 0, offsetof(mavlink_auth_key_t, key) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_AUTH_KEY { \ - "AUTH_KEY", \ - 1, \ - { { "key", NULL, MAVLINK_TYPE_CHAR, 32, 0, offsetof(mavlink_auth_key_t, key) }, \ - } \ -} -#endif - -/** - * @brief Pack a auth_key message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param key key - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_auth_key_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - const char *key) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_AUTH_KEY_LEN]; - - _mav_put_char_array(buf, 0, key, 32); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_AUTH_KEY_LEN); -#else - mavlink_auth_key_t packet; - - mav_array_memcpy(packet.key, key, sizeof(char)*32); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_AUTH_KEY_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_AUTH_KEY; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_AUTH_KEY_MIN_LEN, MAVLINK_MSG_ID_AUTH_KEY_LEN, MAVLINK_MSG_ID_AUTH_KEY_CRC); -} - -/** - * @brief Pack a auth_key message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param key key - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_auth_key_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - const char *key) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_AUTH_KEY_LEN]; - - _mav_put_char_array(buf, 0, key, 32); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_AUTH_KEY_LEN); -#else - mavlink_auth_key_t packet; - - mav_array_memcpy(packet.key, key, sizeof(char)*32); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_AUTH_KEY_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_AUTH_KEY; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_AUTH_KEY_MIN_LEN, MAVLINK_MSG_ID_AUTH_KEY_LEN, MAVLINK_MSG_ID_AUTH_KEY_CRC); -} - -/** - * @brief Encode a auth_key struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param auth_key C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_auth_key_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_auth_key_t* auth_key) -{ - return mavlink_msg_auth_key_pack(system_id, component_id, msg, auth_key->key); -} - -/** - * @brief Encode a auth_key struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param auth_key C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_auth_key_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_auth_key_t* auth_key) -{ - return mavlink_msg_auth_key_pack_chan(system_id, component_id, chan, msg, auth_key->key); -} - -/** - * @brief Send a auth_key message - * @param chan MAVLink channel to send the message - * - * @param key key - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_auth_key_send(mavlink_channel_t chan, const char *key) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_AUTH_KEY_LEN]; - - _mav_put_char_array(buf, 0, key, 32); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTH_KEY, buf, MAVLINK_MSG_ID_AUTH_KEY_MIN_LEN, MAVLINK_MSG_ID_AUTH_KEY_LEN, MAVLINK_MSG_ID_AUTH_KEY_CRC); -#else - mavlink_auth_key_t packet; - - mav_array_memcpy(packet.key, key, sizeof(char)*32); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTH_KEY, (const char *)&packet, MAVLINK_MSG_ID_AUTH_KEY_MIN_LEN, MAVLINK_MSG_ID_AUTH_KEY_LEN, MAVLINK_MSG_ID_AUTH_KEY_CRC); -#endif -} - -/** - * @brief Send a auth_key message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_auth_key_send_struct(mavlink_channel_t chan, const mavlink_auth_key_t* auth_key) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_auth_key_send(chan, auth_key->key); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTH_KEY, (const char *)auth_key, MAVLINK_MSG_ID_AUTH_KEY_MIN_LEN, MAVLINK_MSG_ID_AUTH_KEY_LEN, MAVLINK_MSG_ID_AUTH_KEY_CRC); -#endif -} - -#if MAVLINK_MSG_ID_AUTH_KEY_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_auth_key_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, const char *key) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - - _mav_put_char_array(buf, 0, key, 32); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTH_KEY, buf, MAVLINK_MSG_ID_AUTH_KEY_MIN_LEN, MAVLINK_MSG_ID_AUTH_KEY_LEN, MAVLINK_MSG_ID_AUTH_KEY_CRC); -#else - mavlink_auth_key_t *packet = (mavlink_auth_key_t *)msgbuf; - - mav_array_memcpy(packet->key, key, sizeof(char)*32); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTH_KEY, (const char *)packet, MAVLINK_MSG_ID_AUTH_KEY_MIN_LEN, MAVLINK_MSG_ID_AUTH_KEY_LEN, MAVLINK_MSG_ID_AUTH_KEY_CRC); -#endif -} -#endif - -#endif - -// MESSAGE AUTH_KEY UNPACKING - - -/** - * @brief Get field key from auth_key message - * - * @return key - */ -static inline uint16_t mavlink_msg_auth_key_get_key(const mavlink_message_t* msg, char *key) -{ - return _MAV_RETURN_char_array(msg, key, 32, 0); -} - -/** - * @brief Decode a auth_key message into a struct - * - * @param msg The message to decode - * @param auth_key C-struct to decode the message contents into - */ -static inline void mavlink_msg_auth_key_decode(const mavlink_message_t* msg, mavlink_auth_key_t* auth_key) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_auth_key_get_key(msg, auth_key->key); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_AUTH_KEY_LEN? msg->len : MAVLINK_MSG_ID_AUTH_KEY_LEN; - memset(auth_key, 0, MAVLINK_MSG_ID_AUTH_KEY_LEN); - memcpy(auth_key, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_autopilot_state_for_gimbal_device.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_autopilot_state_for_gimbal_device.h deleted file mode 100644 index 062f6a02..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_autopilot_state_for_gimbal_device.h +++ /dev/null @@ -1,505 +0,0 @@ -#pragma once -// MESSAGE AUTOPILOT_STATE_FOR_GIMBAL_DEVICE PACKING - -#define MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE 286 - -MAVPACKED( -typedef struct __mavlink_autopilot_state_for_gimbal_device_t { - uint64_t time_boot_us; /*< [us] Timestamp (time since system boot).*/ - float q[4]; /*< Quaternion components of autopilot attitude: w, x, y, z (1 0 0 0 is the null-rotation, Hamilton convention).*/ - uint32_t q_estimated_delay_us; /*< [us] Estimated delay of the attitude data. 0 if unknown.*/ - float vx; /*< [m/s] X Speed in NED (North, East, Down). NAN if unknown.*/ - float vy; /*< [m/s] Y Speed in NED (North, East, Down). NAN if unknown.*/ - float vz; /*< [m/s] Z Speed in NED (North, East, Down). NAN if unknown.*/ - uint32_t v_estimated_delay_us; /*< [us] Estimated delay of the speed data. 0 if unknown.*/ - float feed_forward_angular_velocity_z; /*< [rad/s] Feed forward Z component of angular velocity (positive: yawing to the right). NaN to be ignored. This is to indicate if the autopilot is actively yawing.*/ - uint16_t estimator_status; /*< Bitmap indicating which estimator outputs are valid.*/ - uint8_t target_system; /*< System ID*/ - uint8_t target_component; /*< Component ID*/ - uint8_t landed_state; /*< The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown.*/ - float angular_velocity_z; /*< [rad/s] Z component of angular velocity in NED (North, East, Down). NaN if unknown.*/ -}) mavlink_autopilot_state_for_gimbal_device_t; - -#define MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_LEN 57 -#define MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_MIN_LEN 53 -#define MAVLINK_MSG_ID_286_LEN 57 -#define MAVLINK_MSG_ID_286_MIN_LEN 53 - -#define MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_CRC 210 -#define MAVLINK_MSG_ID_286_CRC 210 - -#define MAVLINK_MSG_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_FIELD_Q_LEN 4 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE { \ - 286, \ - "AUTOPILOT_STATE_FOR_GIMBAL_DEVICE", \ - 13, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 50, offsetof(mavlink_autopilot_state_for_gimbal_device_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 51, offsetof(mavlink_autopilot_state_for_gimbal_device_t, target_component) }, \ - { "time_boot_us", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_autopilot_state_for_gimbal_device_t, time_boot_us) }, \ - { "q", NULL, MAVLINK_TYPE_FLOAT, 4, 8, offsetof(mavlink_autopilot_state_for_gimbal_device_t, q) }, \ - { "q_estimated_delay_us", NULL, MAVLINK_TYPE_UINT32_T, 0, 24, offsetof(mavlink_autopilot_state_for_gimbal_device_t, q_estimated_delay_us) }, \ - { "vx", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_autopilot_state_for_gimbal_device_t, vx) }, \ - { "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_autopilot_state_for_gimbal_device_t, vy) }, \ - { "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_autopilot_state_for_gimbal_device_t, vz) }, \ - { "v_estimated_delay_us", NULL, MAVLINK_TYPE_UINT32_T, 0, 40, offsetof(mavlink_autopilot_state_for_gimbal_device_t, v_estimated_delay_us) }, \ - { "feed_forward_angular_velocity_z", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_autopilot_state_for_gimbal_device_t, feed_forward_angular_velocity_z) }, \ - { "estimator_status", NULL, MAVLINK_TYPE_UINT16_T, 0, 48, offsetof(mavlink_autopilot_state_for_gimbal_device_t, estimator_status) }, \ - { "landed_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 52, offsetof(mavlink_autopilot_state_for_gimbal_device_t, landed_state) }, \ - { "angular_velocity_z", NULL, MAVLINK_TYPE_FLOAT, 0, 53, offsetof(mavlink_autopilot_state_for_gimbal_device_t, angular_velocity_z) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE { \ - "AUTOPILOT_STATE_FOR_GIMBAL_DEVICE", \ - 13, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 50, offsetof(mavlink_autopilot_state_for_gimbal_device_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 51, offsetof(mavlink_autopilot_state_for_gimbal_device_t, target_component) }, \ - { "time_boot_us", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_autopilot_state_for_gimbal_device_t, time_boot_us) }, \ - { "q", NULL, MAVLINK_TYPE_FLOAT, 4, 8, offsetof(mavlink_autopilot_state_for_gimbal_device_t, q) }, \ - { "q_estimated_delay_us", NULL, MAVLINK_TYPE_UINT32_T, 0, 24, offsetof(mavlink_autopilot_state_for_gimbal_device_t, q_estimated_delay_us) }, \ - { "vx", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_autopilot_state_for_gimbal_device_t, vx) }, \ - { "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_autopilot_state_for_gimbal_device_t, vy) }, \ - { "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_autopilot_state_for_gimbal_device_t, vz) }, \ - { "v_estimated_delay_us", NULL, MAVLINK_TYPE_UINT32_T, 0, 40, offsetof(mavlink_autopilot_state_for_gimbal_device_t, v_estimated_delay_us) }, \ - { "feed_forward_angular_velocity_z", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_autopilot_state_for_gimbal_device_t, feed_forward_angular_velocity_z) }, \ - { "estimator_status", NULL, MAVLINK_TYPE_UINT16_T, 0, 48, offsetof(mavlink_autopilot_state_for_gimbal_device_t, estimator_status) }, \ - { "landed_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 52, offsetof(mavlink_autopilot_state_for_gimbal_device_t, landed_state) }, \ - { "angular_velocity_z", NULL, MAVLINK_TYPE_FLOAT, 0, 53, offsetof(mavlink_autopilot_state_for_gimbal_device_t, angular_velocity_z) }, \ - } \ -} -#endif - -/** - * @brief Pack a autopilot_state_for_gimbal_device message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID - * @param target_component Component ID - * @param time_boot_us [us] Timestamp (time since system boot). - * @param q Quaternion components of autopilot attitude: w, x, y, z (1 0 0 0 is the null-rotation, Hamilton convention). - * @param q_estimated_delay_us [us] Estimated delay of the attitude data. 0 if unknown. - * @param vx [m/s] X Speed in NED (North, East, Down). NAN if unknown. - * @param vy [m/s] Y Speed in NED (North, East, Down). NAN if unknown. - * @param vz [m/s] Z Speed in NED (North, East, Down). NAN if unknown. - * @param v_estimated_delay_us [us] Estimated delay of the speed data. 0 if unknown. - * @param feed_forward_angular_velocity_z [rad/s] Feed forward Z component of angular velocity (positive: yawing to the right). NaN to be ignored. This is to indicate if the autopilot is actively yawing. - * @param estimator_status Bitmap indicating which estimator outputs are valid. - * @param landed_state The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown. - * @param angular_velocity_z [rad/s] Z component of angular velocity in NED (North, East, Down). NaN if unknown. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_autopilot_state_for_gimbal_device_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component, uint64_t time_boot_us, const float *q, uint32_t q_estimated_delay_us, float vx, float vy, float vz, uint32_t v_estimated_delay_us, float feed_forward_angular_velocity_z, uint16_t estimator_status, uint8_t landed_state, float angular_velocity_z) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_LEN]; - _mav_put_uint64_t(buf, 0, time_boot_us); - _mav_put_uint32_t(buf, 24, q_estimated_delay_us); - _mav_put_float(buf, 28, vx); - _mav_put_float(buf, 32, vy); - _mav_put_float(buf, 36, vz); - _mav_put_uint32_t(buf, 40, v_estimated_delay_us); - _mav_put_float(buf, 44, feed_forward_angular_velocity_z); - _mav_put_uint16_t(buf, 48, estimator_status); - _mav_put_uint8_t(buf, 50, target_system); - _mav_put_uint8_t(buf, 51, target_component); - _mav_put_uint8_t(buf, 52, landed_state); - _mav_put_float(buf, 53, angular_velocity_z); - _mav_put_float_array(buf, 8, q, 4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_LEN); -#else - mavlink_autopilot_state_for_gimbal_device_t packet; - packet.time_boot_us = time_boot_us; - packet.q_estimated_delay_us = q_estimated_delay_us; - packet.vx = vx; - packet.vy = vy; - packet.vz = vz; - packet.v_estimated_delay_us = v_estimated_delay_us; - packet.feed_forward_angular_velocity_z = feed_forward_angular_velocity_z; - packet.estimator_status = estimator_status; - packet.target_system = target_system; - packet.target_component = target_component; - packet.landed_state = landed_state; - packet.angular_velocity_z = angular_velocity_z; - mav_array_memcpy(packet.q, q, sizeof(float)*4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_MIN_LEN, MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_LEN, MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_CRC); -} - -/** - * @brief Pack a autopilot_state_for_gimbal_device message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @param time_boot_us [us] Timestamp (time since system boot). - * @param q Quaternion components of autopilot attitude: w, x, y, z (1 0 0 0 is the null-rotation, Hamilton convention). - * @param q_estimated_delay_us [us] Estimated delay of the attitude data. 0 if unknown. - * @param vx [m/s] X Speed in NED (North, East, Down). NAN if unknown. - * @param vy [m/s] Y Speed in NED (North, East, Down). NAN if unknown. - * @param vz [m/s] Z Speed in NED (North, East, Down). NAN if unknown. - * @param v_estimated_delay_us [us] Estimated delay of the speed data. 0 if unknown. - * @param feed_forward_angular_velocity_z [rad/s] Feed forward Z component of angular velocity (positive: yawing to the right). NaN to be ignored. This is to indicate if the autopilot is actively yawing. - * @param estimator_status Bitmap indicating which estimator outputs are valid. - * @param landed_state The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown. - * @param angular_velocity_z [rad/s] Z component of angular velocity in NED (North, East, Down). NaN if unknown. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_autopilot_state_for_gimbal_device_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component,uint64_t time_boot_us,const float *q,uint32_t q_estimated_delay_us,float vx,float vy,float vz,uint32_t v_estimated_delay_us,float feed_forward_angular_velocity_z,uint16_t estimator_status,uint8_t landed_state,float angular_velocity_z) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_LEN]; - _mav_put_uint64_t(buf, 0, time_boot_us); - _mav_put_uint32_t(buf, 24, q_estimated_delay_us); - _mav_put_float(buf, 28, vx); - _mav_put_float(buf, 32, vy); - _mav_put_float(buf, 36, vz); - _mav_put_uint32_t(buf, 40, v_estimated_delay_us); - _mav_put_float(buf, 44, feed_forward_angular_velocity_z); - _mav_put_uint16_t(buf, 48, estimator_status); - _mav_put_uint8_t(buf, 50, target_system); - _mav_put_uint8_t(buf, 51, target_component); - _mav_put_uint8_t(buf, 52, landed_state); - _mav_put_float(buf, 53, angular_velocity_z); - _mav_put_float_array(buf, 8, q, 4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_LEN); -#else - mavlink_autopilot_state_for_gimbal_device_t packet; - packet.time_boot_us = time_boot_us; - packet.q_estimated_delay_us = q_estimated_delay_us; - packet.vx = vx; - packet.vy = vy; - packet.vz = vz; - packet.v_estimated_delay_us = v_estimated_delay_us; - packet.feed_forward_angular_velocity_z = feed_forward_angular_velocity_z; - packet.estimator_status = estimator_status; - packet.target_system = target_system; - packet.target_component = target_component; - packet.landed_state = landed_state; - packet.angular_velocity_z = angular_velocity_z; - mav_array_memcpy(packet.q, q, sizeof(float)*4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_MIN_LEN, MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_LEN, MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_CRC); -} - -/** - * @brief Encode a autopilot_state_for_gimbal_device struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param autopilot_state_for_gimbal_device C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_autopilot_state_for_gimbal_device_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_autopilot_state_for_gimbal_device_t* autopilot_state_for_gimbal_device) -{ - return mavlink_msg_autopilot_state_for_gimbal_device_pack(system_id, component_id, msg, autopilot_state_for_gimbal_device->target_system, autopilot_state_for_gimbal_device->target_component, autopilot_state_for_gimbal_device->time_boot_us, autopilot_state_for_gimbal_device->q, autopilot_state_for_gimbal_device->q_estimated_delay_us, autopilot_state_for_gimbal_device->vx, autopilot_state_for_gimbal_device->vy, autopilot_state_for_gimbal_device->vz, autopilot_state_for_gimbal_device->v_estimated_delay_us, autopilot_state_for_gimbal_device->feed_forward_angular_velocity_z, autopilot_state_for_gimbal_device->estimator_status, autopilot_state_for_gimbal_device->landed_state, autopilot_state_for_gimbal_device->angular_velocity_z); -} - -/** - * @brief Encode a autopilot_state_for_gimbal_device struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param autopilot_state_for_gimbal_device C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_autopilot_state_for_gimbal_device_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_autopilot_state_for_gimbal_device_t* autopilot_state_for_gimbal_device) -{ - return mavlink_msg_autopilot_state_for_gimbal_device_pack_chan(system_id, component_id, chan, msg, autopilot_state_for_gimbal_device->target_system, autopilot_state_for_gimbal_device->target_component, autopilot_state_for_gimbal_device->time_boot_us, autopilot_state_for_gimbal_device->q, autopilot_state_for_gimbal_device->q_estimated_delay_us, autopilot_state_for_gimbal_device->vx, autopilot_state_for_gimbal_device->vy, autopilot_state_for_gimbal_device->vz, autopilot_state_for_gimbal_device->v_estimated_delay_us, autopilot_state_for_gimbal_device->feed_forward_angular_velocity_z, autopilot_state_for_gimbal_device->estimator_status, autopilot_state_for_gimbal_device->landed_state, autopilot_state_for_gimbal_device->angular_velocity_z); -} - -/** - * @brief Send a autopilot_state_for_gimbal_device message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param target_component Component ID - * @param time_boot_us [us] Timestamp (time since system boot). - * @param q Quaternion components of autopilot attitude: w, x, y, z (1 0 0 0 is the null-rotation, Hamilton convention). - * @param q_estimated_delay_us [us] Estimated delay of the attitude data. 0 if unknown. - * @param vx [m/s] X Speed in NED (North, East, Down). NAN if unknown. - * @param vy [m/s] Y Speed in NED (North, East, Down). NAN if unknown. - * @param vz [m/s] Z Speed in NED (North, East, Down). NAN if unknown. - * @param v_estimated_delay_us [us] Estimated delay of the speed data. 0 if unknown. - * @param feed_forward_angular_velocity_z [rad/s] Feed forward Z component of angular velocity (positive: yawing to the right). NaN to be ignored. This is to indicate if the autopilot is actively yawing. - * @param estimator_status Bitmap indicating which estimator outputs are valid. - * @param landed_state The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown. - * @param angular_velocity_z [rad/s] Z component of angular velocity in NED (North, East, Down). NaN if unknown. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_autopilot_state_for_gimbal_device_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint64_t time_boot_us, const float *q, uint32_t q_estimated_delay_us, float vx, float vy, float vz, uint32_t v_estimated_delay_us, float feed_forward_angular_velocity_z, uint16_t estimator_status, uint8_t landed_state, float angular_velocity_z) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_LEN]; - _mav_put_uint64_t(buf, 0, time_boot_us); - _mav_put_uint32_t(buf, 24, q_estimated_delay_us); - _mav_put_float(buf, 28, vx); - _mav_put_float(buf, 32, vy); - _mav_put_float(buf, 36, vz); - _mav_put_uint32_t(buf, 40, v_estimated_delay_us); - _mav_put_float(buf, 44, feed_forward_angular_velocity_z); - _mav_put_uint16_t(buf, 48, estimator_status); - _mav_put_uint8_t(buf, 50, target_system); - _mav_put_uint8_t(buf, 51, target_component); - _mav_put_uint8_t(buf, 52, landed_state); - _mav_put_float(buf, 53, angular_velocity_z); - _mav_put_float_array(buf, 8, q, 4); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE, buf, MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_MIN_LEN, MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_LEN, MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_CRC); -#else - mavlink_autopilot_state_for_gimbal_device_t packet; - packet.time_boot_us = time_boot_us; - packet.q_estimated_delay_us = q_estimated_delay_us; - packet.vx = vx; - packet.vy = vy; - packet.vz = vz; - packet.v_estimated_delay_us = v_estimated_delay_us; - packet.feed_forward_angular_velocity_z = feed_forward_angular_velocity_z; - packet.estimator_status = estimator_status; - packet.target_system = target_system; - packet.target_component = target_component; - packet.landed_state = landed_state; - packet.angular_velocity_z = angular_velocity_z; - mav_array_memcpy(packet.q, q, sizeof(float)*4); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE, (const char *)&packet, MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_MIN_LEN, MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_LEN, MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_CRC); -#endif -} - -/** - * @brief Send a autopilot_state_for_gimbal_device message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_autopilot_state_for_gimbal_device_send_struct(mavlink_channel_t chan, const mavlink_autopilot_state_for_gimbal_device_t* autopilot_state_for_gimbal_device) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_autopilot_state_for_gimbal_device_send(chan, autopilot_state_for_gimbal_device->target_system, autopilot_state_for_gimbal_device->target_component, autopilot_state_for_gimbal_device->time_boot_us, autopilot_state_for_gimbal_device->q, autopilot_state_for_gimbal_device->q_estimated_delay_us, autopilot_state_for_gimbal_device->vx, autopilot_state_for_gimbal_device->vy, autopilot_state_for_gimbal_device->vz, autopilot_state_for_gimbal_device->v_estimated_delay_us, autopilot_state_for_gimbal_device->feed_forward_angular_velocity_z, autopilot_state_for_gimbal_device->estimator_status, autopilot_state_for_gimbal_device->landed_state, autopilot_state_for_gimbal_device->angular_velocity_z); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE, (const char *)autopilot_state_for_gimbal_device, MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_MIN_LEN, MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_LEN, MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_CRC); -#endif -} - -#if MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_autopilot_state_for_gimbal_device_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint64_t time_boot_us, const float *q, uint32_t q_estimated_delay_us, float vx, float vy, float vz, uint32_t v_estimated_delay_us, float feed_forward_angular_velocity_z, uint16_t estimator_status, uint8_t landed_state, float angular_velocity_z) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, time_boot_us); - _mav_put_uint32_t(buf, 24, q_estimated_delay_us); - _mav_put_float(buf, 28, vx); - _mav_put_float(buf, 32, vy); - _mav_put_float(buf, 36, vz); - _mav_put_uint32_t(buf, 40, v_estimated_delay_us); - _mav_put_float(buf, 44, feed_forward_angular_velocity_z); - _mav_put_uint16_t(buf, 48, estimator_status); - _mav_put_uint8_t(buf, 50, target_system); - _mav_put_uint8_t(buf, 51, target_component); - _mav_put_uint8_t(buf, 52, landed_state); - _mav_put_float(buf, 53, angular_velocity_z); - _mav_put_float_array(buf, 8, q, 4); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE, buf, MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_MIN_LEN, MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_LEN, MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_CRC); -#else - mavlink_autopilot_state_for_gimbal_device_t *packet = (mavlink_autopilot_state_for_gimbal_device_t *)msgbuf; - packet->time_boot_us = time_boot_us; - packet->q_estimated_delay_us = q_estimated_delay_us; - packet->vx = vx; - packet->vy = vy; - packet->vz = vz; - packet->v_estimated_delay_us = v_estimated_delay_us; - packet->feed_forward_angular_velocity_z = feed_forward_angular_velocity_z; - packet->estimator_status = estimator_status; - packet->target_system = target_system; - packet->target_component = target_component; - packet->landed_state = landed_state; - packet->angular_velocity_z = angular_velocity_z; - mav_array_memcpy(packet->q, q, sizeof(float)*4); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE, (const char *)packet, MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_MIN_LEN, MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_LEN, MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_CRC); -#endif -} -#endif - -#endif - -// MESSAGE AUTOPILOT_STATE_FOR_GIMBAL_DEVICE UNPACKING - - -/** - * @brief Get field target_system from autopilot_state_for_gimbal_device message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_autopilot_state_for_gimbal_device_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 50); -} - -/** - * @brief Get field target_component from autopilot_state_for_gimbal_device message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_autopilot_state_for_gimbal_device_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 51); -} - -/** - * @brief Get field time_boot_us from autopilot_state_for_gimbal_device message - * - * @return [us] Timestamp (time since system boot). - */ -static inline uint64_t mavlink_msg_autopilot_state_for_gimbal_device_get_time_boot_us(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field q from autopilot_state_for_gimbal_device message - * - * @return Quaternion components of autopilot attitude: w, x, y, z (1 0 0 0 is the null-rotation, Hamilton convention). - */ -static inline uint16_t mavlink_msg_autopilot_state_for_gimbal_device_get_q(const mavlink_message_t* msg, float *q) -{ - return _MAV_RETURN_float_array(msg, q, 4, 8); -} - -/** - * @brief Get field q_estimated_delay_us from autopilot_state_for_gimbal_device message - * - * @return [us] Estimated delay of the attitude data. 0 if unknown. - */ -static inline uint32_t mavlink_msg_autopilot_state_for_gimbal_device_get_q_estimated_delay_us(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 24); -} - -/** - * @brief Get field vx from autopilot_state_for_gimbal_device message - * - * @return [m/s] X Speed in NED (North, East, Down). NAN if unknown. - */ -static inline float mavlink_msg_autopilot_state_for_gimbal_device_get_vx(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 28); -} - -/** - * @brief Get field vy from autopilot_state_for_gimbal_device message - * - * @return [m/s] Y Speed in NED (North, East, Down). NAN if unknown. - */ -static inline float mavlink_msg_autopilot_state_for_gimbal_device_get_vy(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 32); -} - -/** - * @brief Get field vz from autopilot_state_for_gimbal_device message - * - * @return [m/s] Z Speed in NED (North, East, Down). NAN if unknown. - */ -static inline float mavlink_msg_autopilot_state_for_gimbal_device_get_vz(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 36); -} - -/** - * @brief Get field v_estimated_delay_us from autopilot_state_for_gimbal_device message - * - * @return [us] Estimated delay of the speed data. 0 if unknown. - */ -static inline uint32_t mavlink_msg_autopilot_state_for_gimbal_device_get_v_estimated_delay_us(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 40); -} - -/** - * @brief Get field feed_forward_angular_velocity_z from autopilot_state_for_gimbal_device message - * - * @return [rad/s] Feed forward Z component of angular velocity (positive: yawing to the right). NaN to be ignored. This is to indicate if the autopilot is actively yawing. - */ -static inline float mavlink_msg_autopilot_state_for_gimbal_device_get_feed_forward_angular_velocity_z(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 44); -} - -/** - * @brief Get field estimator_status from autopilot_state_for_gimbal_device message - * - * @return Bitmap indicating which estimator outputs are valid. - */ -static inline uint16_t mavlink_msg_autopilot_state_for_gimbal_device_get_estimator_status(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 48); -} - -/** - * @brief Get field landed_state from autopilot_state_for_gimbal_device message - * - * @return The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown. - */ -static inline uint8_t mavlink_msg_autopilot_state_for_gimbal_device_get_landed_state(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 52); -} - -/** - * @brief Get field angular_velocity_z from autopilot_state_for_gimbal_device message - * - * @return [rad/s] Z component of angular velocity in NED (North, East, Down). NaN if unknown. - */ -static inline float mavlink_msg_autopilot_state_for_gimbal_device_get_angular_velocity_z(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 53); -} - -/** - * @brief Decode a autopilot_state_for_gimbal_device message into a struct - * - * @param msg The message to decode - * @param autopilot_state_for_gimbal_device C-struct to decode the message contents into - */ -static inline void mavlink_msg_autopilot_state_for_gimbal_device_decode(const mavlink_message_t* msg, mavlink_autopilot_state_for_gimbal_device_t* autopilot_state_for_gimbal_device) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - autopilot_state_for_gimbal_device->time_boot_us = mavlink_msg_autopilot_state_for_gimbal_device_get_time_boot_us(msg); - mavlink_msg_autopilot_state_for_gimbal_device_get_q(msg, autopilot_state_for_gimbal_device->q); - autopilot_state_for_gimbal_device->q_estimated_delay_us = mavlink_msg_autopilot_state_for_gimbal_device_get_q_estimated_delay_us(msg); - autopilot_state_for_gimbal_device->vx = mavlink_msg_autopilot_state_for_gimbal_device_get_vx(msg); - autopilot_state_for_gimbal_device->vy = mavlink_msg_autopilot_state_for_gimbal_device_get_vy(msg); - autopilot_state_for_gimbal_device->vz = mavlink_msg_autopilot_state_for_gimbal_device_get_vz(msg); - autopilot_state_for_gimbal_device->v_estimated_delay_us = mavlink_msg_autopilot_state_for_gimbal_device_get_v_estimated_delay_us(msg); - autopilot_state_for_gimbal_device->feed_forward_angular_velocity_z = mavlink_msg_autopilot_state_for_gimbal_device_get_feed_forward_angular_velocity_z(msg); - autopilot_state_for_gimbal_device->estimator_status = mavlink_msg_autopilot_state_for_gimbal_device_get_estimator_status(msg); - autopilot_state_for_gimbal_device->target_system = mavlink_msg_autopilot_state_for_gimbal_device_get_target_system(msg); - autopilot_state_for_gimbal_device->target_component = mavlink_msg_autopilot_state_for_gimbal_device_get_target_component(msg); - autopilot_state_for_gimbal_device->landed_state = mavlink_msg_autopilot_state_for_gimbal_device_get_landed_state(msg); - autopilot_state_for_gimbal_device->angular_velocity_z = mavlink_msg_autopilot_state_for_gimbal_device_get_angular_velocity_z(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_LEN? msg->len : MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_LEN; - memset(autopilot_state_for_gimbal_device, 0, MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_LEN); - memcpy(autopilot_state_for_gimbal_device, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_autopilot_version.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_autopilot_version.h deleted file mode 100644 index 85df0d4e..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_autopilot_version.h +++ /dev/null @@ -1,483 +0,0 @@ -#pragma once -// MESSAGE AUTOPILOT_VERSION PACKING - -#define MAVLINK_MSG_ID_AUTOPILOT_VERSION 148 - - -typedef struct __mavlink_autopilot_version_t { - uint64_t capabilities; /*< Bitmap of capabilities*/ - uint64_t uid; /*< UID if provided by hardware (see uid2)*/ - uint32_t flight_sw_version; /*< Firmware version number*/ - uint32_t middleware_sw_version; /*< Middleware version number*/ - uint32_t os_sw_version; /*< Operating system version number*/ - uint32_t board_version; /*< HW / board version (last 8 bits should be silicon ID, if any). The first 16 bits of this field specify https://github.com/PX4/PX4-Bootloader/blob/master/board_types.txt*/ - uint16_t vendor_id; /*< ID of the board vendor*/ - uint16_t product_id; /*< ID of the product*/ - uint8_t flight_custom_version[8]; /*< Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases.*/ - uint8_t middleware_custom_version[8]; /*< Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases.*/ - uint8_t os_custom_version[8]; /*< Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases.*/ - uint8_t uid2[18]; /*< UID if provided by hardware (supersedes the uid field. If this is non-zero, use this field, otherwise use uid)*/ -} mavlink_autopilot_version_t; - -#define MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN 78 -#define MAVLINK_MSG_ID_AUTOPILOT_VERSION_MIN_LEN 60 -#define MAVLINK_MSG_ID_148_LEN 78 -#define MAVLINK_MSG_ID_148_MIN_LEN 60 - -#define MAVLINK_MSG_ID_AUTOPILOT_VERSION_CRC 178 -#define MAVLINK_MSG_ID_148_CRC 178 - -#define MAVLINK_MSG_AUTOPILOT_VERSION_FIELD_FLIGHT_CUSTOM_VERSION_LEN 8 -#define MAVLINK_MSG_AUTOPILOT_VERSION_FIELD_MIDDLEWARE_CUSTOM_VERSION_LEN 8 -#define MAVLINK_MSG_AUTOPILOT_VERSION_FIELD_OS_CUSTOM_VERSION_LEN 8 -#define MAVLINK_MSG_AUTOPILOT_VERSION_FIELD_UID2_LEN 18 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_AUTOPILOT_VERSION { \ - 148, \ - "AUTOPILOT_VERSION", \ - 12, \ - { { "capabilities", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_autopilot_version_t, capabilities) }, \ - { "flight_sw_version", NULL, MAVLINK_TYPE_UINT32_T, 0, 16, offsetof(mavlink_autopilot_version_t, flight_sw_version) }, \ - { "middleware_sw_version", NULL, MAVLINK_TYPE_UINT32_T, 0, 20, offsetof(mavlink_autopilot_version_t, middleware_sw_version) }, \ - { "os_sw_version", NULL, MAVLINK_TYPE_UINT32_T, 0, 24, offsetof(mavlink_autopilot_version_t, os_sw_version) }, \ - { "board_version", NULL, MAVLINK_TYPE_UINT32_T, 0, 28, offsetof(mavlink_autopilot_version_t, board_version) }, \ - { "flight_custom_version", NULL, MAVLINK_TYPE_UINT8_T, 8, 36, offsetof(mavlink_autopilot_version_t, flight_custom_version) }, \ - { "middleware_custom_version", NULL, MAVLINK_TYPE_UINT8_T, 8, 44, offsetof(mavlink_autopilot_version_t, middleware_custom_version) }, \ - { "os_custom_version", NULL, MAVLINK_TYPE_UINT8_T, 8, 52, offsetof(mavlink_autopilot_version_t, os_custom_version) }, \ - { "vendor_id", NULL, MAVLINK_TYPE_UINT16_T, 0, 32, offsetof(mavlink_autopilot_version_t, vendor_id) }, \ - { "product_id", NULL, MAVLINK_TYPE_UINT16_T, 0, 34, offsetof(mavlink_autopilot_version_t, product_id) }, \ - { "uid", NULL, MAVLINK_TYPE_UINT64_T, 0, 8, offsetof(mavlink_autopilot_version_t, uid) }, \ - { "uid2", NULL, MAVLINK_TYPE_UINT8_T, 18, 60, offsetof(mavlink_autopilot_version_t, uid2) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_AUTOPILOT_VERSION { \ - "AUTOPILOT_VERSION", \ - 12, \ - { { "capabilities", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_autopilot_version_t, capabilities) }, \ - { "flight_sw_version", NULL, MAVLINK_TYPE_UINT32_T, 0, 16, offsetof(mavlink_autopilot_version_t, flight_sw_version) }, \ - { "middleware_sw_version", NULL, MAVLINK_TYPE_UINT32_T, 0, 20, offsetof(mavlink_autopilot_version_t, middleware_sw_version) }, \ - { "os_sw_version", NULL, MAVLINK_TYPE_UINT32_T, 0, 24, offsetof(mavlink_autopilot_version_t, os_sw_version) }, \ - { "board_version", NULL, MAVLINK_TYPE_UINT32_T, 0, 28, offsetof(mavlink_autopilot_version_t, board_version) }, \ - { "flight_custom_version", NULL, MAVLINK_TYPE_UINT8_T, 8, 36, offsetof(mavlink_autopilot_version_t, flight_custom_version) }, \ - { "middleware_custom_version", NULL, MAVLINK_TYPE_UINT8_T, 8, 44, offsetof(mavlink_autopilot_version_t, middleware_custom_version) }, \ - { "os_custom_version", NULL, MAVLINK_TYPE_UINT8_T, 8, 52, offsetof(mavlink_autopilot_version_t, os_custom_version) }, \ - { "vendor_id", NULL, MAVLINK_TYPE_UINT16_T, 0, 32, offsetof(mavlink_autopilot_version_t, vendor_id) }, \ - { "product_id", NULL, MAVLINK_TYPE_UINT16_T, 0, 34, offsetof(mavlink_autopilot_version_t, product_id) }, \ - { "uid", NULL, MAVLINK_TYPE_UINT64_T, 0, 8, offsetof(mavlink_autopilot_version_t, uid) }, \ - { "uid2", NULL, MAVLINK_TYPE_UINT8_T, 18, 60, offsetof(mavlink_autopilot_version_t, uid2) }, \ - } \ -} -#endif - -/** - * @brief Pack a autopilot_version message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param capabilities Bitmap of capabilities - * @param flight_sw_version Firmware version number - * @param middleware_sw_version Middleware version number - * @param os_sw_version Operating system version number - * @param board_version HW / board version (last 8 bits should be silicon ID, if any). The first 16 bits of this field specify https://github.com/PX4/PX4-Bootloader/blob/master/board_types.txt - * @param flight_custom_version Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. - * @param middleware_custom_version Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. - * @param os_custom_version Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. - * @param vendor_id ID of the board vendor - * @param product_id ID of the product - * @param uid UID if provided by hardware (see uid2) - * @param uid2 UID if provided by hardware (supersedes the uid field. If this is non-zero, use this field, otherwise use uid) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_autopilot_version_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint64_t capabilities, uint32_t flight_sw_version, uint32_t middleware_sw_version, uint32_t os_sw_version, uint32_t board_version, const uint8_t *flight_custom_version, const uint8_t *middleware_custom_version, const uint8_t *os_custom_version, uint16_t vendor_id, uint16_t product_id, uint64_t uid, const uint8_t *uid2) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN]; - _mav_put_uint64_t(buf, 0, capabilities); - _mav_put_uint64_t(buf, 8, uid); - _mav_put_uint32_t(buf, 16, flight_sw_version); - _mav_put_uint32_t(buf, 20, middleware_sw_version); - _mav_put_uint32_t(buf, 24, os_sw_version); - _mav_put_uint32_t(buf, 28, board_version); - _mav_put_uint16_t(buf, 32, vendor_id); - _mav_put_uint16_t(buf, 34, product_id); - _mav_put_uint8_t_array(buf, 36, flight_custom_version, 8); - _mav_put_uint8_t_array(buf, 44, middleware_custom_version, 8); - _mav_put_uint8_t_array(buf, 52, os_custom_version, 8); - _mav_put_uint8_t_array(buf, 60, uid2, 18); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN); -#else - mavlink_autopilot_version_t packet; - packet.capabilities = capabilities; - packet.uid = uid; - packet.flight_sw_version = flight_sw_version; - packet.middleware_sw_version = middleware_sw_version; - packet.os_sw_version = os_sw_version; - packet.board_version = board_version; - packet.vendor_id = vendor_id; - packet.product_id = product_id; - mav_array_memcpy(packet.flight_custom_version, flight_custom_version, sizeof(uint8_t)*8); - mav_array_memcpy(packet.middleware_custom_version, middleware_custom_version, sizeof(uint8_t)*8); - mav_array_memcpy(packet.os_custom_version, os_custom_version, sizeof(uint8_t)*8); - mav_array_memcpy(packet.uid2, uid2, sizeof(uint8_t)*18); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_AUTOPILOT_VERSION; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_AUTOPILOT_VERSION_MIN_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_CRC); -} - -/** - * @brief Pack a autopilot_version message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param capabilities Bitmap of capabilities - * @param flight_sw_version Firmware version number - * @param middleware_sw_version Middleware version number - * @param os_sw_version Operating system version number - * @param board_version HW / board version (last 8 bits should be silicon ID, if any). The first 16 bits of this field specify https://github.com/PX4/PX4-Bootloader/blob/master/board_types.txt - * @param flight_custom_version Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. - * @param middleware_custom_version Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. - * @param os_custom_version Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. - * @param vendor_id ID of the board vendor - * @param product_id ID of the product - * @param uid UID if provided by hardware (see uid2) - * @param uid2 UID if provided by hardware (supersedes the uid field. If this is non-zero, use this field, otherwise use uid) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_autopilot_version_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint64_t capabilities,uint32_t flight_sw_version,uint32_t middleware_sw_version,uint32_t os_sw_version,uint32_t board_version,const uint8_t *flight_custom_version,const uint8_t *middleware_custom_version,const uint8_t *os_custom_version,uint16_t vendor_id,uint16_t product_id,uint64_t uid,const uint8_t *uid2) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN]; - _mav_put_uint64_t(buf, 0, capabilities); - _mav_put_uint64_t(buf, 8, uid); - _mav_put_uint32_t(buf, 16, flight_sw_version); - _mav_put_uint32_t(buf, 20, middleware_sw_version); - _mav_put_uint32_t(buf, 24, os_sw_version); - _mav_put_uint32_t(buf, 28, board_version); - _mav_put_uint16_t(buf, 32, vendor_id); - _mav_put_uint16_t(buf, 34, product_id); - _mav_put_uint8_t_array(buf, 36, flight_custom_version, 8); - _mav_put_uint8_t_array(buf, 44, middleware_custom_version, 8); - _mav_put_uint8_t_array(buf, 52, os_custom_version, 8); - _mav_put_uint8_t_array(buf, 60, uid2, 18); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN); -#else - mavlink_autopilot_version_t packet; - packet.capabilities = capabilities; - packet.uid = uid; - packet.flight_sw_version = flight_sw_version; - packet.middleware_sw_version = middleware_sw_version; - packet.os_sw_version = os_sw_version; - packet.board_version = board_version; - packet.vendor_id = vendor_id; - packet.product_id = product_id; - mav_array_memcpy(packet.flight_custom_version, flight_custom_version, sizeof(uint8_t)*8); - mav_array_memcpy(packet.middleware_custom_version, middleware_custom_version, sizeof(uint8_t)*8); - mav_array_memcpy(packet.os_custom_version, os_custom_version, sizeof(uint8_t)*8); - mav_array_memcpy(packet.uid2, uid2, sizeof(uint8_t)*18); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_AUTOPILOT_VERSION; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_AUTOPILOT_VERSION_MIN_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_CRC); -} - -/** - * @brief Encode a autopilot_version struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param autopilot_version C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_autopilot_version_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_autopilot_version_t* autopilot_version) -{ - return mavlink_msg_autopilot_version_pack(system_id, component_id, msg, autopilot_version->capabilities, autopilot_version->flight_sw_version, autopilot_version->middleware_sw_version, autopilot_version->os_sw_version, autopilot_version->board_version, autopilot_version->flight_custom_version, autopilot_version->middleware_custom_version, autopilot_version->os_custom_version, autopilot_version->vendor_id, autopilot_version->product_id, autopilot_version->uid, autopilot_version->uid2); -} - -/** - * @brief Encode a autopilot_version struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param autopilot_version C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_autopilot_version_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_autopilot_version_t* autopilot_version) -{ - return mavlink_msg_autopilot_version_pack_chan(system_id, component_id, chan, msg, autopilot_version->capabilities, autopilot_version->flight_sw_version, autopilot_version->middleware_sw_version, autopilot_version->os_sw_version, autopilot_version->board_version, autopilot_version->flight_custom_version, autopilot_version->middleware_custom_version, autopilot_version->os_custom_version, autopilot_version->vendor_id, autopilot_version->product_id, autopilot_version->uid, autopilot_version->uid2); -} - -/** - * @brief Send a autopilot_version message - * @param chan MAVLink channel to send the message - * - * @param capabilities Bitmap of capabilities - * @param flight_sw_version Firmware version number - * @param middleware_sw_version Middleware version number - * @param os_sw_version Operating system version number - * @param board_version HW / board version (last 8 bits should be silicon ID, if any). The first 16 bits of this field specify https://github.com/PX4/PX4-Bootloader/blob/master/board_types.txt - * @param flight_custom_version Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. - * @param middleware_custom_version Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. - * @param os_custom_version Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. - * @param vendor_id ID of the board vendor - * @param product_id ID of the product - * @param uid UID if provided by hardware (see uid2) - * @param uid2 UID if provided by hardware (supersedes the uid field. If this is non-zero, use this field, otherwise use uid) - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_autopilot_version_send(mavlink_channel_t chan, uint64_t capabilities, uint32_t flight_sw_version, uint32_t middleware_sw_version, uint32_t os_sw_version, uint32_t board_version, const uint8_t *flight_custom_version, const uint8_t *middleware_custom_version, const uint8_t *os_custom_version, uint16_t vendor_id, uint16_t product_id, uint64_t uid, const uint8_t *uid2) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN]; - _mav_put_uint64_t(buf, 0, capabilities); - _mav_put_uint64_t(buf, 8, uid); - _mav_put_uint32_t(buf, 16, flight_sw_version); - _mav_put_uint32_t(buf, 20, middleware_sw_version); - _mav_put_uint32_t(buf, 24, os_sw_version); - _mav_put_uint32_t(buf, 28, board_version); - _mav_put_uint16_t(buf, 32, vendor_id); - _mav_put_uint16_t(buf, 34, product_id); - _mav_put_uint8_t_array(buf, 36, flight_custom_version, 8); - _mav_put_uint8_t_array(buf, 44, middleware_custom_version, 8); - _mav_put_uint8_t_array(buf, 52, os_custom_version, 8); - _mav_put_uint8_t_array(buf, 60, uid2, 18); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTOPILOT_VERSION, buf, MAVLINK_MSG_ID_AUTOPILOT_VERSION_MIN_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_CRC); -#else - mavlink_autopilot_version_t packet; - packet.capabilities = capabilities; - packet.uid = uid; - packet.flight_sw_version = flight_sw_version; - packet.middleware_sw_version = middleware_sw_version; - packet.os_sw_version = os_sw_version; - packet.board_version = board_version; - packet.vendor_id = vendor_id; - packet.product_id = product_id; - mav_array_memcpy(packet.flight_custom_version, flight_custom_version, sizeof(uint8_t)*8); - mav_array_memcpy(packet.middleware_custom_version, middleware_custom_version, sizeof(uint8_t)*8); - mav_array_memcpy(packet.os_custom_version, os_custom_version, sizeof(uint8_t)*8); - mav_array_memcpy(packet.uid2, uid2, sizeof(uint8_t)*18); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTOPILOT_VERSION, (const char *)&packet, MAVLINK_MSG_ID_AUTOPILOT_VERSION_MIN_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_CRC); -#endif -} - -/** - * @brief Send a autopilot_version message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_autopilot_version_send_struct(mavlink_channel_t chan, const mavlink_autopilot_version_t* autopilot_version) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_autopilot_version_send(chan, autopilot_version->capabilities, autopilot_version->flight_sw_version, autopilot_version->middleware_sw_version, autopilot_version->os_sw_version, autopilot_version->board_version, autopilot_version->flight_custom_version, autopilot_version->middleware_custom_version, autopilot_version->os_custom_version, autopilot_version->vendor_id, autopilot_version->product_id, autopilot_version->uid, autopilot_version->uid2); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTOPILOT_VERSION, (const char *)autopilot_version, MAVLINK_MSG_ID_AUTOPILOT_VERSION_MIN_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_CRC); -#endif -} - -#if MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_autopilot_version_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t capabilities, uint32_t flight_sw_version, uint32_t middleware_sw_version, uint32_t os_sw_version, uint32_t board_version, const uint8_t *flight_custom_version, const uint8_t *middleware_custom_version, const uint8_t *os_custom_version, uint16_t vendor_id, uint16_t product_id, uint64_t uid, const uint8_t *uid2) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, capabilities); - _mav_put_uint64_t(buf, 8, uid); - _mav_put_uint32_t(buf, 16, flight_sw_version); - _mav_put_uint32_t(buf, 20, middleware_sw_version); - _mav_put_uint32_t(buf, 24, os_sw_version); - _mav_put_uint32_t(buf, 28, board_version); - _mav_put_uint16_t(buf, 32, vendor_id); - _mav_put_uint16_t(buf, 34, product_id); - _mav_put_uint8_t_array(buf, 36, flight_custom_version, 8); - _mav_put_uint8_t_array(buf, 44, middleware_custom_version, 8); - _mav_put_uint8_t_array(buf, 52, os_custom_version, 8); - _mav_put_uint8_t_array(buf, 60, uid2, 18); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTOPILOT_VERSION, buf, MAVLINK_MSG_ID_AUTOPILOT_VERSION_MIN_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_CRC); -#else - mavlink_autopilot_version_t *packet = (mavlink_autopilot_version_t *)msgbuf; - packet->capabilities = capabilities; - packet->uid = uid; - packet->flight_sw_version = flight_sw_version; - packet->middleware_sw_version = middleware_sw_version; - packet->os_sw_version = os_sw_version; - packet->board_version = board_version; - packet->vendor_id = vendor_id; - packet->product_id = product_id; - mav_array_memcpy(packet->flight_custom_version, flight_custom_version, sizeof(uint8_t)*8); - mav_array_memcpy(packet->middleware_custom_version, middleware_custom_version, sizeof(uint8_t)*8); - mav_array_memcpy(packet->os_custom_version, os_custom_version, sizeof(uint8_t)*8); - mav_array_memcpy(packet->uid2, uid2, sizeof(uint8_t)*18); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTOPILOT_VERSION, (const char *)packet, MAVLINK_MSG_ID_AUTOPILOT_VERSION_MIN_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_CRC); -#endif -} -#endif - -#endif - -// MESSAGE AUTOPILOT_VERSION UNPACKING - - -/** - * @brief Get field capabilities from autopilot_version message - * - * @return Bitmap of capabilities - */ -static inline uint64_t mavlink_msg_autopilot_version_get_capabilities(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field flight_sw_version from autopilot_version message - * - * @return Firmware version number - */ -static inline uint32_t mavlink_msg_autopilot_version_get_flight_sw_version(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 16); -} - -/** - * @brief Get field middleware_sw_version from autopilot_version message - * - * @return Middleware version number - */ -static inline uint32_t mavlink_msg_autopilot_version_get_middleware_sw_version(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 20); -} - -/** - * @brief Get field os_sw_version from autopilot_version message - * - * @return Operating system version number - */ -static inline uint32_t mavlink_msg_autopilot_version_get_os_sw_version(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 24); -} - -/** - * @brief Get field board_version from autopilot_version message - * - * @return HW / board version (last 8 bits should be silicon ID, if any). The first 16 bits of this field specify https://github.com/PX4/PX4-Bootloader/blob/master/board_types.txt - */ -static inline uint32_t mavlink_msg_autopilot_version_get_board_version(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 28); -} - -/** - * @brief Get field flight_custom_version from autopilot_version message - * - * @return Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. - */ -static inline uint16_t mavlink_msg_autopilot_version_get_flight_custom_version(const mavlink_message_t* msg, uint8_t *flight_custom_version) -{ - return _MAV_RETURN_uint8_t_array(msg, flight_custom_version, 8, 36); -} - -/** - * @brief Get field middleware_custom_version from autopilot_version message - * - * @return Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. - */ -static inline uint16_t mavlink_msg_autopilot_version_get_middleware_custom_version(const mavlink_message_t* msg, uint8_t *middleware_custom_version) -{ - return _MAV_RETURN_uint8_t_array(msg, middleware_custom_version, 8, 44); -} - -/** - * @brief Get field os_custom_version from autopilot_version message - * - * @return Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. - */ -static inline uint16_t mavlink_msg_autopilot_version_get_os_custom_version(const mavlink_message_t* msg, uint8_t *os_custom_version) -{ - return _MAV_RETURN_uint8_t_array(msg, os_custom_version, 8, 52); -} - -/** - * @brief Get field vendor_id from autopilot_version message - * - * @return ID of the board vendor - */ -static inline uint16_t mavlink_msg_autopilot_version_get_vendor_id(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 32); -} - -/** - * @brief Get field product_id from autopilot_version message - * - * @return ID of the product - */ -static inline uint16_t mavlink_msg_autopilot_version_get_product_id(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 34); -} - -/** - * @brief Get field uid from autopilot_version message - * - * @return UID if provided by hardware (see uid2) - */ -static inline uint64_t mavlink_msg_autopilot_version_get_uid(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 8); -} - -/** - * @brief Get field uid2 from autopilot_version message - * - * @return UID if provided by hardware (supersedes the uid field. If this is non-zero, use this field, otherwise use uid) - */ -static inline uint16_t mavlink_msg_autopilot_version_get_uid2(const mavlink_message_t* msg, uint8_t *uid2) -{ - return _MAV_RETURN_uint8_t_array(msg, uid2, 18, 60); -} - -/** - * @brief Decode a autopilot_version message into a struct - * - * @param msg The message to decode - * @param autopilot_version C-struct to decode the message contents into - */ -static inline void mavlink_msg_autopilot_version_decode(const mavlink_message_t* msg, mavlink_autopilot_version_t* autopilot_version) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - autopilot_version->capabilities = mavlink_msg_autopilot_version_get_capabilities(msg); - autopilot_version->uid = mavlink_msg_autopilot_version_get_uid(msg); - autopilot_version->flight_sw_version = mavlink_msg_autopilot_version_get_flight_sw_version(msg); - autopilot_version->middleware_sw_version = mavlink_msg_autopilot_version_get_middleware_sw_version(msg); - autopilot_version->os_sw_version = mavlink_msg_autopilot_version_get_os_sw_version(msg); - autopilot_version->board_version = mavlink_msg_autopilot_version_get_board_version(msg); - autopilot_version->vendor_id = mavlink_msg_autopilot_version_get_vendor_id(msg); - autopilot_version->product_id = mavlink_msg_autopilot_version_get_product_id(msg); - mavlink_msg_autopilot_version_get_flight_custom_version(msg, autopilot_version->flight_custom_version); - mavlink_msg_autopilot_version_get_middleware_custom_version(msg, autopilot_version->middleware_custom_version); - mavlink_msg_autopilot_version_get_os_custom_version(msg, autopilot_version->os_custom_version); - mavlink_msg_autopilot_version_get_uid2(msg, autopilot_version->uid2); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN? msg->len : MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN; - memset(autopilot_version, 0, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN); - memcpy(autopilot_version, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_battery_status.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_battery_status.h deleted file mode 100644 index 357c483e..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_battery_status.h +++ /dev/null @@ -1,531 +0,0 @@ -#pragma once -// MESSAGE BATTERY_STATUS PACKING - -#define MAVLINK_MSG_ID_BATTERY_STATUS 147 - -MAVPACKED( -typedef struct __mavlink_battery_status_t { - int32_t current_consumed; /*< [mAh] Consumed charge, -1: autopilot does not provide consumption estimate*/ - int32_t energy_consumed; /*< [hJ] Consumed energy, -1: autopilot does not provide energy consumption estimate*/ - int16_t temperature; /*< [cdegC] Temperature of the battery. INT16_MAX for unknown temperature.*/ - uint16_t voltages[10]; /*< [mV] Battery voltage of cells 1 to 10 (see voltages_ext for cells 11-14). Cells in this field above the valid cell count for this battery should have the UINT16_MAX value. If individual cell voltages are unknown or not measured for this battery, then the overall battery voltage should be filled in cell 0, with all others set to UINT16_MAX. If the voltage of the battery is greater than (UINT16_MAX - 1), then cell 0 should be set to (UINT16_MAX - 1), and cell 1 to the remaining voltage. This can be extended to multiple cells if the total voltage is greater than 2 * (UINT16_MAX - 1).*/ - int16_t current_battery; /*< [cA] Battery current, -1: autopilot does not measure the current*/ - uint8_t id; /*< Battery ID*/ - uint8_t battery_function; /*< Function of the battery*/ - uint8_t type; /*< Type (chemistry) of the battery*/ - int8_t battery_remaining; /*< [%] Remaining battery energy. Values: [0-100], -1: autopilot does not estimate the remaining battery.*/ - int32_t time_remaining; /*< [s] Remaining battery time, 0: autopilot does not provide remaining battery time estimate*/ - uint8_t charge_state; /*< State for extent of discharge, provided by autopilot for warning or external reactions*/ - uint16_t voltages_ext[4]; /*< [mV] Battery voltages for cells 11 to 14. Cells above the valid cell count for this battery should have a value of 0, where zero indicates not supported (note, this is different than for the voltages field and allows empty byte truncation). If the measured value is 0 then 1 should be sent instead.*/ - uint8_t mode; /*< Battery mode. Default (0) is that battery mode reporting is not supported or battery is in normal-use mode.*/ - uint32_t fault_bitmask; /*< Fault/health indications. These should be set when charge_state is MAV_BATTERY_CHARGE_STATE_FAILED or MAV_BATTERY_CHARGE_STATE_UNHEALTHY (if not, fault reporting is not supported).*/ -}) mavlink_battery_status_t; - -#define MAVLINK_MSG_ID_BATTERY_STATUS_LEN 54 -#define MAVLINK_MSG_ID_BATTERY_STATUS_MIN_LEN 36 -#define MAVLINK_MSG_ID_147_LEN 54 -#define MAVLINK_MSG_ID_147_MIN_LEN 36 - -#define MAVLINK_MSG_ID_BATTERY_STATUS_CRC 154 -#define MAVLINK_MSG_ID_147_CRC 154 - -#define MAVLINK_MSG_BATTERY_STATUS_FIELD_VOLTAGES_LEN 10 -#define MAVLINK_MSG_BATTERY_STATUS_FIELD_VOLTAGES_EXT_LEN 4 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_BATTERY_STATUS { \ - 147, \ - "BATTERY_STATUS", \ - 14, \ - { { "id", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_battery_status_t, id) }, \ - { "battery_function", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_battery_status_t, battery_function) }, \ - { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_battery_status_t, type) }, \ - { "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_battery_status_t, temperature) }, \ - { "voltages", NULL, MAVLINK_TYPE_UINT16_T, 10, 10, offsetof(mavlink_battery_status_t, voltages) }, \ - { "current_battery", NULL, MAVLINK_TYPE_INT16_T, 0, 30, offsetof(mavlink_battery_status_t, current_battery) }, \ - { "current_consumed", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_battery_status_t, current_consumed) }, \ - { "energy_consumed", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_battery_status_t, energy_consumed) }, \ - { "battery_remaining", NULL, MAVLINK_TYPE_INT8_T, 0, 35, offsetof(mavlink_battery_status_t, battery_remaining) }, \ - { "time_remaining", NULL, MAVLINK_TYPE_INT32_T, 0, 36, offsetof(mavlink_battery_status_t, time_remaining) }, \ - { "charge_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 40, offsetof(mavlink_battery_status_t, charge_state) }, \ - { "voltages_ext", NULL, MAVLINK_TYPE_UINT16_T, 4, 41, offsetof(mavlink_battery_status_t, voltages_ext) }, \ - { "mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 49, offsetof(mavlink_battery_status_t, mode) }, \ - { "fault_bitmask", NULL, MAVLINK_TYPE_UINT32_T, 0, 50, offsetof(mavlink_battery_status_t, fault_bitmask) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_BATTERY_STATUS { \ - "BATTERY_STATUS", \ - 14, \ - { { "id", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_battery_status_t, id) }, \ - { "battery_function", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_battery_status_t, battery_function) }, \ - { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_battery_status_t, type) }, \ - { "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_battery_status_t, temperature) }, \ - { "voltages", NULL, MAVLINK_TYPE_UINT16_T, 10, 10, offsetof(mavlink_battery_status_t, voltages) }, \ - { "current_battery", NULL, MAVLINK_TYPE_INT16_T, 0, 30, offsetof(mavlink_battery_status_t, current_battery) }, \ - { "current_consumed", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_battery_status_t, current_consumed) }, \ - { "energy_consumed", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_battery_status_t, energy_consumed) }, \ - { "battery_remaining", NULL, MAVLINK_TYPE_INT8_T, 0, 35, offsetof(mavlink_battery_status_t, battery_remaining) }, \ - { "time_remaining", NULL, MAVLINK_TYPE_INT32_T, 0, 36, offsetof(mavlink_battery_status_t, time_remaining) }, \ - { "charge_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 40, offsetof(mavlink_battery_status_t, charge_state) }, \ - { "voltages_ext", NULL, MAVLINK_TYPE_UINT16_T, 4, 41, offsetof(mavlink_battery_status_t, voltages_ext) }, \ - { "mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 49, offsetof(mavlink_battery_status_t, mode) }, \ - { "fault_bitmask", NULL, MAVLINK_TYPE_UINT32_T, 0, 50, offsetof(mavlink_battery_status_t, fault_bitmask) }, \ - } \ -} -#endif - -/** - * @brief Pack a battery_status message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param id Battery ID - * @param battery_function Function of the battery - * @param type Type (chemistry) of the battery - * @param temperature [cdegC] Temperature of the battery. INT16_MAX for unknown temperature. - * @param voltages [mV] Battery voltage of cells 1 to 10 (see voltages_ext for cells 11-14). Cells in this field above the valid cell count for this battery should have the UINT16_MAX value. If individual cell voltages are unknown or not measured for this battery, then the overall battery voltage should be filled in cell 0, with all others set to UINT16_MAX. If the voltage of the battery is greater than (UINT16_MAX - 1), then cell 0 should be set to (UINT16_MAX - 1), and cell 1 to the remaining voltage. This can be extended to multiple cells if the total voltage is greater than 2 * (UINT16_MAX - 1). - * @param current_battery [cA] Battery current, -1: autopilot does not measure the current - * @param current_consumed [mAh] Consumed charge, -1: autopilot does not provide consumption estimate - * @param energy_consumed [hJ] Consumed energy, -1: autopilot does not provide energy consumption estimate - * @param battery_remaining [%] Remaining battery energy. Values: [0-100], -1: autopilot does not estimate the remaining battery. - * @param time_remaining [s] Remaining battery time, 0: autopilot does not provide remaining battery time estimate - * @param charge_state State for extent of discharge, provided by autopilot for warning or external reactions - * @param voltages_ext [mV] Battery voltages for cells 11 to 14. Cells above the valid cell count for this battery should have a value of 0, where zero indicates not supported (note, this is different than for the voltages field and allows empty byte truncation). If the measured value is 0 then 1 should be sent instead. - * @param mode Battery mode. Default (0) is that battery mode reporting is not supported or battery is in normal-use mode. - * @param fault_bitmask Fault/health indications. These should be set when charge_state is MAV_BATTERY_CHARGE_STATE_FAILED or MAV_BATTERY_CHARGE_STATE_UNHEALTHY (if not, fault reporting is not supported). - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_battery_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t id, uint8_t battery_function, uint8_t type, int16_t temperature, const uint16_t *voltages, int16_t current_battery, int32_t current_consumed, int32_t energy_consumed, int8_t battery_remaining, int32_t time_remaining, uint8_t charge_state, const uint16_t *voltages_ext, uint8_t mode, uint32_t fault_bitmask) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_BATTERY_STATUS_LEN]; - _mav_put_int32_t(buf, 0, current_consumed); - _mav_put_int32_t(buf, 4, energy_consumed); - _mav_put_int16_t(buf, 8, temperature); - _mav_put_int16_t(buf, 30, current_battery); - _mav_put_uint8_t(buf, 32, id); - _mav_put_uint8_t(buf, 33, battery_function); - _mav_put_uint8_t(buf, 34, type); - _mav_put_int8_t(buf, 35, battery_remaining); - _mav_put_int32_t(buf, 36, time_remaining); - _mav_put_uint8_t(buf, 40, charge_state); - _mav_put_uint8_t(buf, 49, mode); - _mav_put_uint32_t(buf, 50, fault_bitmask); - _mav_put_uint16_t_array(buf, 10, voltages, 10); - _mav_put_uint16_t_array(buf, 41, voltages_ext, 4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_BATTERY_STATUS_LEN); -#else - mavlink_battery_status_t packet; - packet.current_consumed = current_consumed; - packet.energy_consumed = energy_consumed; - packet.temperature = temperature; - packet.current_battery = current_battery; - packet.id = id; - packet.battery_function = battery_function; - packet.type = type; - packet.battery_remaining = battery_remaining; - packet.time_remaining = time_remaining; - packet.charge_state = charge_state; - packet.mode = mode; - packet.fault_bitmask = fault_bitmask; - mav_array_memcpy(packet.voltages, voltages, sizeof(uint16_t)*10); - mav_array_memcpy(packet.voltages_ext, voltages_ext, sizeof(uint16_t)*4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_BATTERY_STATUS_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_BATTERY_STATUS; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_BATTERY_STATUS_MIN_LEN, MAVLINK_MSG_ID_BATTERY_STATUS_LEN, MAVLINK_MSG_ID_BATTERY_STATUS_CRC); -} - -/** - * @brief Pack a battery_status message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param id Battery ID - * @param battery_function Function of the battery - * @param type Type (chemistry) of the battery - * @param temperature [cdegC] Temperature of the battery. INT16_MAX for unknown temperature. - * @param voltages [mV] Battery voltage of cells 1 to 10 (see voltages_ext for cells 11-14). Cells in this field above the valid cell count for this battery should have the UINT16_MAX value. If individual cell voltages are unknown or not measured for this battery, then the overall battery voltage should be filled in cell 0, with all others set to UINT16_MAX. If the voltage of the battery is greater than (UINT16_MAX - 1), then cell 0 should be set to (UINT16_MAX - 1), and cell 1 to the remaining voltage. This can be extended to multiple cells if the total voltage is greater than 2 * (UINT16_MAX - 1). - * @param current_battery [cA] Battery current, -1: autopilot does not measure the current - * @param current_consumed [mAh] Consumed charge, -1: autopilot does not provide consumption estimate - * @param energy_consumed [hJ] Consumed energy, -1: autopilot does not provide energy consumption estimate - * @param battery_remaining [%] Remaining battery energy. Values: [0-100], -1: autopilot does not estimate the remaining battery. - * @param time_remaining [s] Remaining battery time, 0: autopilot does not provide remaining battery time estimate - * @param charge_state State for extent of discharge, provided by autopilot for warning or external reactions - * @param voltages_ext [mV] Battery voltages for cells 11 to 14. Cells above the valid cell count for this battery should have a value of 0, where zero indicates not supported (note, this is different than for the voltages field and allows empty byte truncation). If the measured value is 0 then 1 should be sent instead. - * @param mode Battery mode. Default (0) is that battery mode reporting is not supported or battery is in normal-use mode. - * @param fault_bitmask Fault/health indications. These should be set when charge_state is MAV_BATTERY_CHARGE_STATE_FAILED or MAV_BATTERY_CHARGE_STATE_UNHEALTHY (if not, fault reporting is not supported). - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_battery_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t id,uint8_t battery_function,uint8_t type,int16_t temperature,const uint16_t *voltages,int16_t current_battery,int32_t current_consumed,int32_t energy_consumed,int8_t battery_remaining,int32_t time_remaining,uint8_t charge_state,const uint16_t *voltages_ext,uint8_t mode,uint32_t fault_bitmask) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_BATTERY_STATUS_LEN]; - _mav_put_int32_t(buf, 0, current_consumed); - _mav_put_int32_t(buf, 4, energy_consumed); - _mav_put_int16_t(buf, 8, temperature); - _mav_put_int16_t(buf, 30, current_battery); - _mav_put_uint8_t(buf, 32, id); - _mav_put_uint8_t(buf, 33, battery_function); - _mav_put_uint8_t(buf, 34, type); - _mav_put_int8_t(buf, 35, battery_remaining); - _mav_put_int32_t(buf, 36, time_remaining); - _mav_put_uint8_t(buf, 40, charge_state); - _mav_put_uint8_t(buf, 49, mode); - _mav_put_uint32_t(buf, 50, fault_bitmask); - _mav_put_uint16_t_array(buf, 10, voltages, 10); - _mav_put_uint16_t_array(buf, 41, voltages_ext, 4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_BATTERY_STATUS_LEN); -#else - mavlink_battery_status_t packet; - packet.current_consumed = current_consumed; - packet.energy_consumed = energy_consumed; - packet.temperature = temperature; - packet.current_battery = current_battery; - packet.id = id; - packet.battery_function = battery_function; - packet.type = type; - packet.battery_remaining = battery_remaining; - packet.time_remaining = time_remaining; - packet.charge_state = charge_state; - packet.mode = mode; - packet.fault_bitmask = fault_bitmask; - mav_array_memcpy(packet.voltages, voltages, sizeof(uint16_t)*10); - mav_array_memcpy(packet.voltages_ext, voltages_ext, sizeof(uint16_t)*4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_BATTERY_STATUS_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_BATTERY_STATUS; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_BATTERY_STATUS_MIN_LEN, MAVLINK_MSG_ID_BATTERY_STATUS_LEN, MAVLINK_MSG_ID_BATTERY_STATUS_CRC); -} - -/** - * @brief Encode a battery_status struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param battery_status C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_battery_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_battery_status_t* battery_status) -{ - return mavlink_msg_battery_status_pack(system_id, component_id, msg, battery_status->id, battery_status->battery_function, battery_status->type, battery_status->temperature, battery_status->voltages, battery_status->current_battery, battery_status->current_consumed, battery_status->energy_consumed, battery_status->battery_remaining, battery_status->time_remaining, battery_status->charge_state, battery_status->voltages_ext, battery_status->mode, battery_status->fault_bitmask); -} - -/** - * @brief Encode a battery_status struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param battery_status C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_battery_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_battery_status_t* battery_status) -{ - return mavlink_msg_battery_status_pack_chan(system_id, component_id, chan, msg, battery_status->id, battery_status->battery_function, battery_status->type, battery_status->temperature, battery_status->voltages, battery_status->current_battery, battery_status->current_consumed, battery_status->energy_consumed, battery_status->battery_remaining, battery_status->time_remaining, battery_status->charge_state, battery_status->voltages_ext, battery_status->mode, battery_status->fault_bitmask); -} - -/** - * @brief Send a battery_status message - * @param chan MAVLink channel to send the message - * - * @param id Battery ID - * @param battery_function Function of the battery - * @param type Type (chemistry) of the battery - * @param temperature [cdegC] Temperature of the battery. INT16_MAX for unknown temperature. - * @param voltages [mV] Battery voltage of cells 1 to 10 (see voltages_ext for cells 11-14). Cells in this field above the valid cell count for this battery should have the UINT16_MAX value. If individual cell voltages are unknown or not measured for this battery, then the overall battery voltage should be filled in cell 0, with all others set to UINT16_MAX. If the voltage of the battery is greater than (UINT16_MAX - 1), then cell 0 should be set to (UINT16_MAX - 1), and cell 1 to the remaining voltage. This can be extended to multiple cells if the total voltage is greater than 2 * (UINT16_MAX - 1). - * @param current_battery [cA] Battery current, -1: autopilot does not measure the current - * @param current_consumed [mAh] Consumed charge, -1: autopilot does not provide consumption estimate - * @param energy_consumed [hJ] Consumed energy, -1: autopilot does not provide energy consumption estimate - * @param battery_remaining [%] Remaining battery energy. Values: [0-100], -1: autopilot does not estimate the remaining battery. - * @param time_remaining [s] Remaining battery time, 0: autopilot does not provide remaining battery time estimate - * @param charge_state State for extent of discharge, provided by autopilot for warning or external reactions - * @param voltages_ext [mV] Battery voltages for cells 11 to 14. Cells above the valid cell count for this battery should have a value of 0, where zero indicates not supported (note, this is different than for the voltages field and allows empty byte truncation). If the measured value is 0 then 1 should be sent instead. - * @param mode Battery mode. Default (0) is that battery mode reporting is not supported or battery is in normal-use mode. - * @param fault_bitmask Fault/health indications. These should be set when charge_state is MAV_BATTERY_CHARGE_STATE_FAILED or MAV_BATTERY_CHARGE_STATE_UNHEALTHY (if not, fault reporting is not supported). - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_battery_status_send(mavlink_channel_t chan, uint8_t id, uint8_t battery_function, uint8_t type, int16_t temperature, const uint16_t *voltages, int16_t current_battery, int32_t current_consumed, int32_t energy_consumed, int8_t battery_remaining, int32_t time_remaining, uint8_t charge_state, const uint16_t *voltages_ext, uint8_t mode, uint32_t fault_bitmask) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_BATTERY_STATUS_LEN]; - _mav_put_int32_t(buf, 0, current_consumed); - _mav_put_int32_t(buf, 4, energy_consumed); - _mav_put_int16_t(buf, 8, temperature); - _mav_put_int16_t(buf, 30, current_battery); - _mav_put_uint8_t(buf, 32, id); - _mav_put_uint8_t(buf, 33, battery_function); - _mav_put_uint8_t(buf, 34, type); - _mav_put_int8_t(buf, 35, battery_remaining); - _mav_put_int32_t(buf, 36, time_remaining); - _mav_put_uint8_t(buf, 40, charge_state); - _mav_put_uint8_t(buf, 49, mode); - _mav_put_uint32_t(buf, 50, fault_bitmask); - _mav_put_uint16_t_array(buf, 10, voltages, 10); - _mav_put_uint16_t_array(buf, 41, voltages_ext, 4); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BATTERY_STATUS, buf, MAVLINK_MSG_ID_BATTERY_STATUS_MIN_LEN, MAVLINK_MSG_ID_BATTERY_STATUS_LEN, MAVLINK_MSG_ID_BATTERY_STATUS_CRC); -#else - mavlink_battery_status_t packet; - packet.current_consumed = current_consumed; - packet.energy_consumed = energy_consumed; - packet.temperature = temperature; - packet.current_battery = current_battery; - packet.id = id; - packet.battery_function = battery_function; - packet.type = type; - packet.battery_remaining = battery_remaining; - packet.time_remaining = time_remaining; - packet.charge_state = charge_state; - packet.mode = mode; - packet.fault_bitmask = fault_bitmask; - mav_array_memcpy(packet.voltages, voltages, sizeof(uint16_t)*10); - mav_array_memcpy(packet.voltages_ext, voltages_ext, sizeof(uint16_t)*4); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BATTERY_STATUS, (const char *)&packet, MAVLINK_MSG_ID_BATTERY_STATUS_MIN_LEN, MAVLINK_MSG_ID_BATTERY_STATUS_LEN, MAVLINK_MSG_ID_BATTERY_STATUS_CRC); -#endif -} - -/** - * @brief Send a battery_status message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_battery_status_send_struct(mavlink_channel_t chan, const mavlink_battery_status_t* battery_status) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_battery_status_send(chan, battery_status->id, battery_status->battery_function, battery_status->type, battery_status->temperature, battery_status->voltages, battery_status->current_battery, battery_status->current_consumed, battery_status->energy_consumed, battery_status->battery_remaining, battery_status->time_remaining, battery_status->charge_state, battery_status->voltages_ext, battery_status->mode, battery_status->fault_bitmask); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BATTERY_STATUS, (const char *)battery_status, MAVLINK_MSG_ID_BATTERY_STATUS_MIN_LEN, MAVLINK_MSG_ID_BATTERY_STATUS_LEN, MAVLINK_MSG_ID_BATTERY_STATUS_CRC); -#endif -} - -#if MAVLINK_MSG_ID_BATTERY_STATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_battery_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t id, uint8_t battery_function, uint8_t type, int16_t temperature, const uint16_t *voltages, int16_t current_battery, int32_t current_consumed, int32_t energy_consumed, int8_t battery_remaining, int32_t time_remaining, uint8_t charge_state, const uint16_t *voltages_ext, uint8_t mode, uint32_t fault_bitmask) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_int32_t(buf, 0, current_consumed); - _mav_put_int32_t(buf, 4, energy_consumed); - _mav_put_int16_t(buf, 8, temperature); - _mav_put_int16_t(buf, 30, current_battery); - _mav_put_uint8_t(buf, 32, id); - _mav_put_uint8_t(buf, 33, battery_function); - _mav_put_uint8_t(buf, 34, type); - _mav_put_int8_t(buf, 35, battery_remaining); - _mav_put_int32_t(buf, 36, time_remaining); - _mav_put_uint8_t(buf, 40, charge_state); - _mav_put_uint8_t(buf, 49, mode); - _mav_put_uint32_t(buf, 50, fault_bitmask); - _mav_put_uint16_t_array(buf, 10, voltages, 10); - _mav_put_uint16_t_array(buf, 41, voltages_ext, 4); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BATTERY_STATUS, buf, MAVLINK_MSG_ID_BATTERY_STATUS_MIN_LEN, MAVLINK_MSG_ID_BATTERY_STATUS_LEN, MAVLINK_MSG_ID_BATTERY_STATUS_CRC); -#else - mavlink_battery_status_t *packet = (mavlink_battery_status_t *)msgbuf; - packet->current_consumed = current_consumed; - packet->energy_consumed = energy_consumed; - packet->temperature = temperature; - packet->current_battery = current_battery; - packet->id = id; - packet->battery_function = battery_function; - packet->type = type; - packet->battery_remaining = battery_remaining; - packet->time_remaining = time_remaining; - packet->charge_state = charge_state; - packet->mode = mode; - packet->fault_bitmask = fault_bitmask; - mav_array_memcpy(packet->voltages, voltages, sizeof(uint16_t)*10); - mav_array_memcpy(packet->voltages_ext, voltages_ext, sizeof(uint16_t)*4); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BATTERY_STATUS, (const char *)packet, MAVLINK_MSG_ID_BATTERY_STATUS_MIN_LEN, MAVLINK_MSG_ID_BATTERY_STATUS_LEN, MAVLINK_MSG_ID_BATTERY_STATUS_CRC); -#endif -} -#endif - -#endif - -// MESSAGE BATTERY_STATUS UNPACKING - - -/** - * @brief Get field id from battery_status message - * - * @return Battery ID - */ -static inline uint8_t mavlink_msg_battery_status_get_id(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 32); -} - -/** - * @brief Get field battery_function from battery_status message - * - * @return Function of the battery - */ -static inline uint8_t mavlink_msg_battery_status_get_battery_function(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 33); -} - -/** - * @brief Get field type from battery_status message - * - * @return Type (chemistry) of the battery - */ -static inline uint8_t mavlink_msg_battery_status_get_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 34); -} - -/** - * @brief Get field temperature from battery_status message - * - * @return [cdegC] Temperature of the battery. INT16_MAX for unknown temperature. - */ -static inline int16_t mavlink_msg_battery_status_get_temperature(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 8); -} - -/** - * @brief Get field voltages from battery_status message - * - * @return [mV] Battery voltage of cells 1 to 10 (see voltages_ext for cells 11-14). Cells in this field above the valid cell count for this battery should have the UINT16_MAX value. If individual cell voltages are unknown or not measured for this battery, then the overall battery voltage should be filled in cell 0, with all others set to UINT16_MAX. If the voltage of the battery is greater than (UINT16_MAX - 1), then cell 0 should be set to (UINT16_MAX - 1), and cell 1 to the remaining voltage. This can be extended to multiple cells if the total voltage is greater than 2 * (UINT16_MAX - 1). - */ -static inline uint16_t mavlink_msg_battery_status_get_voltages(const mavlink_message_t* msg, uint16_t *voltages) -{ - return _MAV_RETURN_uint16_t_array(msg, voltages, 10, 10); -} - -/** - * @brief Get field current_battery from battery_status message - * - * @return [cA] Battery current, -1: autopilot does not measure the current - */ -static inline int16_t mavlink_msg_battery_status_get_current_battery(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 30); -} - -/** - * @brief Get field current_consumed from battery_status message - * - * @return [mAh] Consumed charge, -1: autopilot does not provide consumption estimate - */ -static inline int32_t mavlink_msg_battery_status_get_current_consumed(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 0); -} - -/** - * @brief Get field energy_consumed from battery_status message - * - * @return [hJ] Consumed energy, -1: autopilot does not provide energy consumption estimate - */ -static inline int32_t mavlink_msg_battery_status_get_energy_consumed(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 4); -} - -/** - * @brief Get field battery_remaining from battery_status message - * - * @return [%] Remaining battery energy. Values: [0-100], -1: autopilot does not estimate the remaining battery. - */ -static inline int8_t mavlink_msg_battery_status_get_battery_remaining(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int8_t(msg, 35); -} - -/** - * @brief Get field time_remaining from battery_status message - * - * @return [s] Remaining battery time, 0: autopilot does not provide remaining battery time estimate - */ -static inline int32_t mavlink_msg_battery_status_get_time_remaining(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 36); -} - -/** - * @brief Get field charge_state from battery_status message - * - * @return State for extent of discharge, provided by autopilot for warning or external reactions - */ -static inline uint8_t mavlink_msg_battery_status_get_charge_state(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 40); -} - -/** - * @brief Get field voltages_ext from battery_status message - * - * @return [mV] Battery voltages for cells 11 to 14. Cells above the valid cell count for this battery should have a value of 0, where zero indicates not supported (note, this is different than for the voltages field and allows empty byte truncation). If the measured value is 0 then 1 should be sent instead. - */ -static inline uint16_t mavlink_msg_battery_status_get_voltages_ext(const mavlink_message_t* msg, uint16_t *voltages_ext) -{ - return _MAV_RETURN_uint16_t_array(msg, voltages_ext, 4, 41); -} - -/** - * @brief Get field mode from battery_status message - * - * @return Battery mode. Default (0) is that battery mode reporting is not supported or battery is in normal-use mode. - */ -static inline uint8_t mavlink_msg_battery_status_get_mode(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 49); -} - -/** - * @brief Get field fault_bitmask from battery_status message - * - * @return Fault/health indications. These should be set when charge_state is MAV_BATTERY_CHARGE_STATE_FAILED or MAV_BATTERY_CHARGE_STATE_UNHEALTHY (if not, fault reporting is not supported). - */ -static inline uint32_t mavlink_msg_battery_status_get_fault_bitmask(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 50); -} - -/** - * @brief Decode a battery_status message into a struct - * - * @param msg The message to decode - * @param battery_status C-struct to decode the message contents into - */ -static inline void mavlink_msg_battery_status_decode(const mavlink_message_t* msg, mavlink_battery_status_t* battery_status) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - battery_status->current_consumed = mavlink_msg_battery_status_get_current_consumed(msg); - battery_status->energy_consumed = mavlink_msg_battery_status_get_energy_consumed(msg); - battery_status->temperature = mavlink_msg_battery_status_get_temperature(msg); - mavlink_msg_battery_status_get_voltages(msg, battery_status->voltages); - battery_status->current_battery = mavlink_msg_battery_status_get_current_battery(msg); - battery_status->id = mavlink_msg_battery_status_get_id(msg); - battery_status->battery_function = mavlink_msg_battery_status_get_battery_function(msg); - battery_status->type = mavlink_msg_battery_status_get_type(msg); - battery_status->battery_remaining = mavlink_msg_battery_status_get_battery_remaining(msg); - battery_status->time_remaining = mavlink_msg_battery_status_get_time_remaining(msg); - battery_status->charge_state = mavlink_msg_battery_status_get_charge_state(msg); - mavlink_msg_battery_status_get_voltages_ext(msg, battery_status->voltages_ext); - battery_status->mode = mavlink_msg_battery_status_get_mode(msg); - battery_status->fault_bitmask = mavlink_msg_battery_status_get_fault_bitmask(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_BATTERY_STATUS_LEN? msg->len : MAVLINK_MSG_ID_BATTERY_STATUS_LEN; - memset(battery_status, 0, MAVLINK_MSG_ID_BATTERY_STATUS_LEN); - memcpy(battery_status, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_button_change.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_button_change.h deleted file mode 100644 index 8de4add2..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_button_change.h +++ /dev/null @@ -1,263 +0,0 @@ -#pragma once -// MESSAGE BUTTON_CHANGE PACKING - -#define MAVLINK_MSG_ID_BUTTON_CHANGE 257 - - -typedef struct __mavlink_button_change_t { - uint32_t time_boot_ms; /*< [ms] Timestamp (time since system boot).*/ - uint32_t last_change_ms; /*< [ms] Time of last change of button state.*/ - uint8_t state; /*< Bitmap for state of buttons.*/ -} mavlink_button_change_t; - -#define MAVLINK_MSG_ID_BUTTON_CHANGE_LEN 9 -#define MAVLINK_MSG_ID_BUTTON_CHANGE_MIN_LEN 9 -#define MAVLINK_MSG_ID_257_LEN 9 -#define MAVLINK_MSG_ID_257_MIN_LEN 9 - -#define MAVLINK_MSG_ID_BUTTON_CHANGE_CRC 131 -#define MAVLINK_MSG_ID_257_CRC 131 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_BUTTON_CHANGE { \ - 257, \ - "BUTTON_CHANGE", \ - 3, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_button_change_t, time_boot_ms) }, \ - { "last_change_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_button_change_t, last_change_ms) }, \ - { "state", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_button_change_t, state) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_BUTTON_CHANGE { \ - "BUTTON_CHANGE", \ - 3, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_button_change_t, time_boot_ms) }, \ - { "last_change_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_button_change_t, last_change_ms) }, \ - { "state", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_button_change_t, state) }, \ - } \ -} -#endif - -/** - * @brief Pack a button_change message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param time_boot_ms [ms] Timestamp (time since system boot). - * @param last_change_ms [ms] Time of last change of button state. - * @param state Bitmap for state of buttons. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_button_change_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint32_t time_boot_ms, uint32_t last_change_ms, uint8_t state) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_BUTTON_CHANGE_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_uint32_t(buf, 4, last_change_ms); - _mav_put_uint8_t(buf, 8, state); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_BUTTON_CHANGE_LEN); -#else - mavlink_button_change_t packet; - packet.time_boot_ms = time_boot_ms; - packet.last_change_ms = last_change_ms; - packet.state = state; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_BUTTON_CHANGE_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_BUTTON_CHANGE; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_BUTTON_CHANGE_MIN_LEN, MAVLINK_MSG_ID_BUTTON_CHANGE_LEN, MAVLINK_MSG_ID_BUTTON_CHANGE_CRC); -} - -/** - * @brief Pack a button_change message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_boot_ms [ms] Timestamp (time since system boot). - * @param last_change_ms [ms] Time of last change of button state. - * @param state Bitmap for state of buttons. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_button_change_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint32_t time_boot_ms,uint32_t last_change_ms,uint8_t state) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_BUTTON_CHANGE_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_uint32_t(buf, 4, last_change_ms); - _mav_put_uint8_t(buf, 8, state); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_BUTTON_CHANGE_LEN); -#else - mavlink_button_change_t packet; - packet.time_boot_ms = time_boot_ms; - packet.last_change_ms = last_change_ms; - packet.state = state; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_BUTTON_CHANGE_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_BUTTON_CHANGE; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_BUTTON_CHANGE_MIN_LEN, MAVLINK_MSG_ID_BUTTON_CHANGE_LEN, MAVLINK_MSG_ID_BUTTON_CHANGE_CRC); -} - -/** - * @brief Encode a button_change struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param button_change C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_button_change_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_button_change_t* button_change) -{ - return mavlink_msg_button_change_pack(system_id, component_id, msg, button_change->time_boot_ms, button_change->last_change_ms, button_change->state); -} - -/** - * @brief Encode a button_change struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param button_change C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_button_change_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_button_change_t* button_change) -{ - return mavlink_msg_button_change_pack_chan(system_id, component_id, chan, msg, button_change->time_boot_ms, button_change->last_change_ms, button_change->state); -} - -/** - * @brief Send a button_change message - * @param chan MAVLink channel to send the message - * - * @param time_boot_ms [ms] Timestamp (time since system boot). - * @param last_change_ms [ms] Time of last change of button state. - * @param state Bitmap for state of buttons. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_button_change_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint32_t last_change_ms, uint8_t state) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_BUTTON_CHANGE_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_uint32_t(buf, 4, last_change_ms); - _mav_put_uint8_t(buf, 8, state); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BUTTON_CHANGE, buf, MAVLINK_MSG_ID_BUTTON_CHANGE_MIN_LEN, MAVLINK_MSG_ID_BUTTON_CHANGE_LEN, MAVLINK_MSG_ID_BUTTON_CHANGE_CRC); -#else - mavlink_button_change_t packet; - packet.time_boot_ms = time_boot_ms; - packet.last_change_ms = last_change_ms; - packet.state = state; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BUTTON_CHANGE, (const char *)&packet, MAVLINK_MSG_ID_BUTTON_CHANGE_MIN_LEN, MAVLINK_MSG_ID_BUTTON_CHANGE_LEN, MAVLINK_MSG_ID_BUTTON_CHANGE_CRC); -#endif -} - -/** - * @brief Send a button_change message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_button_change_send_struct(mavlink_channel_t chan, const mavlink_button_change_t* button_change) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_button_change_send(chan, button_change->time_boot_ms, button_change->last_change_ms, button_change->state); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BUTTON_CHANGE, (const char *)button_change, MAVLINK_MSG_ID_BUTTON_CHANGE_MIN_LEN, MAVLINK_MSG_ID_BUTTON_CHANGE_LEN, MAVLINK_MSG_ID_BUTTON_CHANGE_CRC); -#endif -} - -#if MAVLINK_MSG_ID_BUTTON_CHANGE_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_button_change_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint32_t last_change_ms, uint8_t state) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_uint32_t(buf, 4, last_change_ms); - _mav_put_uint8_t(buf, 8, state); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BUTTON_CHANGE, buf, MAVLINK_MSG_ID_BUTTON_CHANGE_MIN_LEN, MAVLINK_MSG_ID_BUTTON_CHANGE_LEN, MAVLINK_MSG_ID_BUTTON_CHANGE_CRC); -#else - mavlink_button_change_t *packet = (mavlink_button_change_t *)msgbuf; - packet->time_boot_ms = time_boot_ms; - packet->last_change_ms = last_change_ms; - packet->state = state; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BUTTON_CHANGE, (const char *)packet, MAVLINK_MSG_ID_BUTTON_CHANGE_MIN_LEN, MAVLINK_MSG_ID_BUTTON_CHANGE_LEN, MAVLINK_MSG_ID_BUTTON_CHANGE_CRC); -#endif -} -#endif - -#endif - -// MESSAGE BUTTON_CHANGE UNPACKING - - -/** - * @brief Get field time_boot_ms from button_change message - * - * @return [ms] Timestamp (time since system boot). - */ -static inline uint32_t mavlink_msg_button_change_get_time_boot_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field last_change_ms from button_change message - * - * @return [ms] Time of last change of button state. - */ -static inline uint32_t mavlink_msg_button_change_get_last_change_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 4); -} - -/** - * @brief Get field state from button_change message - * - * @return Bitmap for state of buttons. - */ -static inline uint8_t mavlink_msg_button_change_get_state(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 8); -} - -/** - * @brief Decode a button_change message into a struct - * - * @param msg The message to decode - * @param button_change C-struct to decode the message contents into - */ -static inline void mavlink_msg_button_change_decode(const mavlink_message_t* msg, mavlink_button_change_t* button_change) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - button_change->time_boot_ms = mavlink_msg_button_change_get_time_boot_ms(msg); - button_change->last_change_ms = mavlink_msg_button_change_get_last_change_ms(msg); - button_change->state = mavlink_msg_button_change_get_state(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_BUTTON_CHANGE_LEN? msg->len : MAVLINK_MSG_ID_BUTTON_CHANGE_LEN; - memset(button_change, 0, MAVLINK_MSG_ID_BUTTON_CHANGE_LEN); - memcpy(button_change, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_camera_capture_status.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_camera_capture_status.h deleted file mode 100644 index 87c3a8c5..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_camera_capture_status.h +++ /dev/null @@ -1,363 +0,0 @@ -#pragma once -// MESSAGE CAMERA_CAPTURE_STATUS PACKING - -#define MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS 262 - -MAVPACKED( -typedef struct __mavlink_camera_capture_status_t { - uint32_t time_boot_ms; /*< [ms] Timestamp (time since system boot).*/ - float image_interval; /*< [s] Image capture interval*/ - uint32_t recording_time_ms; /*< [ms] Elapsed time since recording started (0: Not supported/available). A GCS should compute recording time and use non-zero values of this field to correct any discrepancy.*/ - float available_capacity; /*< [MiB] Available storage capacity.*/ - uint8_t image_status; /*< Current status of image capturing (0: idle, 1: capture in progress, 2: interval set but idle, 3: interval set and capture in progress)*/ - uint8_t video_status; /*< Current status of video capturing (0: idle, 1: capture in progress)*/ - int32_t image_count; /*< Total number of images captured ('forever', or until reset using MAV_CMD_STORAGE_FORMAT).*/ -}) mavlink_camera_capture_status_t; - -#define MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS_LEN 22 -#define MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS_MIN_LEN 18 -#define MAVLINK_MSG_ID_262_LEN 22 -#define MAVLINK_MSG_ID_262_MIN_LEN 18 - -#define MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS_CRC 12 -#define MAVLINK_MSG_ID_262_CRC 12 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_CAMERA_CAPTURE_STATUS { \ - 262, \ - "CAMERA_CAPTURE_STATUS", \ - 7, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_camera_capture_status_t, time_boot_ms) }, \ - { "image_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_camera_capture_status_t, image_status) }, \ - { "video_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 17, offsetof(mavlink_camera_capture_status_t, video_status) }, \ - { "image_interval", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_camera_capture_status_t, image_interval) }, \ - { "recording_time_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_camera_capture_status_t, recording_time_ms) }, \ - { "available_capacity", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_camera_capture_status_t, available_capacity) }, \ - { "image_count", NULL, MAVLINK_TYPE_INT32_T, 0, 18, offsetof(mavlink_camera_capture_status_t, image_count) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_CAMERA_CAPTURE_STATUS { \ - "CAMERA_CAPTURE_STATUS", \ - 7, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_camera_capture_status_t, time_boot_ms) }, \ - { "image_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_camera_capture_status_t, image_status) }, \ - { "video_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 17, offsetof(mavlink_camera_capture_status_t, video_status) }, \ - { "image_interval", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_camera_capture_status_t, image_interval) }, \ - { "recording_time_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_camera_capture_status_t, recording_time_ms) }, \ - { "available_capacity", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_camera_capture_status_t, available_capacity) }, \ - { "image_count", NULL, MAVLINK_TYPE_INT32_T, 0, 18, offsetof(mavlink_camera_capture_status_t, image_count) }, \ - } \ -} -#endif - -/** - * @brief Pack a camera_capture_status message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param time_boot_ms [ms] Timestamp (time since system boot). - * @param image_status Current status of image capturing (0: idle, 1: capture in progress, 2: interval set but idle, 3: interval set and capture in progress) - * @param video_status Current status of video capturing (0: idle, 1: capture in progress) - * @param image_interval [s] Image capture interval - * @param recording_time_ms [ms] Elapsed time since recording started (0: Not supported/available). A GCS should compute recording time and use non-zero values of this field to correct any discrepancy. - * @param available_capacity [MiB] Available storage capacity. - * @param image_count Total number of images captured ('forever', or until reset using MAV_CMD_STORAGE_FORMAT). - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_camera_capture_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint32_t time_boot_ms, uint8_t image_status, uint8_t video_status, float image_interval, uint32_t recording_time_ms, float available_capacity, int32_t image_count) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, image_interval); - _mav_put_uint32_t(buf, 8, recording_time_ms); - _mav_put_float(buf, 12, available_capacity); - _mav_put_uint8_t(buf, 16, image_status); - _mav_put_uint8_t(buf, 17, video_status); - _mav_put_int32_t(buf, 18, image_count); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS_LEN); -#else - mavlink_camera_capture_status_t packet; - packet.time_boot_ms = time_boot_ms; - packet.image_interval = image_interval; - packet.recording_time_ms = recording_time_ms; - packet.available_capacity = available_capacity; - packet.image_status = image_status; - packet.video_status = video_status; - packet.image_count = image_count; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS_MIN_LEN, MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS_LEN, MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS_CRC); -} - -/** - * @brief Pack a camera_capture_status message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_boot_ms [ms] Timestamp (time since system boot). - * @param image_status Current status of image capturing (0: idle, 1: capture in progress, 2: interval set but idle, 3: interval set and capture in progress) - * @param video_status Current status of video capturing (0: idle, 1: capture in progress) - * @param image_interval [s] Image capture interval - * @param recording_time_ms [ms] Elapsed time since recording started (0: Not supported/available). A GCS should compute recording time and use non-zero values of this field to correct any discrepancy. - * @param available_capacity [MiB] Available storage capacity. - * @param image_count Total number of images captured ('forever', or until reset using MAV_CMD_STORAGE_FORMAT). - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_camera_capture_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint32_t time_boot_ms,uint8_t image_status,uint8_t video_status,float image_interval,uint32_t recording_time_ms,float available_capacity,int32_t image_count) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, image_interval); - _mav_put_uint32_t(buf, 8, recording_time_ms); - _mav_put_float(buf, 12, available_capacity); - _mav_put_uint8_t(buf, 16, image_status); - _mav_put_uint8_t(buf, 17, video_status); - _mav_put_int32_t(buf, 18, image_count); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS_LEN); -#else - mavlink_camera_capture_status_t packet; - packet.time_boot_ms = time_boot_ms; - packet.image_interval = image_interval; - packet.recording_time_ms = recording_time_ms; - packet.available_capacity = available_capacity; - packet.image_status = image_status; - packet.video_status = video_status; - packet.image_count = image_count; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS_MIN_LEN, MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS_LEN, MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS_CRC); -} - -/** - * @brief Encode a camera_capture_status struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param camera_capture_status C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_camera_capture_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_camera_capture_status_t* camera_capture_status) -{ - return mavlink_msg_camera_capture_status_pack(system_id, component_id, msg, camera_capture_status->time_boot_ms, camera_capture_status->image_status, camera_capture_status->video_status, camera_capture_status->image_interval, camera_capture_status->recording_time_ms, camera_capture_status->available_capacity, camera_capture_status->image_count); -} - -/** - * @brief Encode a camera_capture_status struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param camera_capture_status C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_camera_capture_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_camera_capture_status_t* camera_capture_status) -{ - return mavlink_msg_camera_capture_status_pack_chan(system_id, component_id, chan, msg, camera_capture_status->time_boot_ms, camera_capture_status->image_status, camera_capture_status->video_status, camera_capture_status->image_interval, camera_capture_status->recording_time_ms, camera_capture_status->available_capacity, camera_capture_status->image_count); -} - -/** - * @brief Send a camera_capture_status message - * @param chan MAVLink channel to send the message - * - * @param time_boot_ms [ms] Timestamp (time since system boot). - * @param image_status Current status of image capturing (0: idle, 1: capture in progress, 2: interval set but idle, 3: interval set and capture in progress) - * @param video_status Current status of video capturing (0: idle, 1: capture in progress) - * @param image_interval [s] Image capture interval - * @param recording_time_ms [ms] Elapsed time since recording started (0: Not supported/available). A GCS should compute recording time and use non-zero values of this field to correct any discrepancy. - * @param available_capacity [MiB] Available storage capacity. - * @param image_count Total number of images captured ('forever', or until reset using MAV_CMD_STORAGE_FORMAT). - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_camera_capture_status_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t image_status, uint8_t video_status, float image_interval, uint32_t recording_time_ms, float available_capacity, int32_t image_count) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, image_interval); - _mav_put_uint32_t(buf, 8, recording_time_ms); - _mav_put_float(buf, 12, available_capacity); - _mav_put_uint8_t(buf, 16, image_status); - _mav_put_uint8_t(buf, 17, video_status); - _mav_put_int32_t(buf, 18, image_count); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS, buf, MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS_MIN_LEN, MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS_LEN, MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS_CRC); -#else - mavlink_camera_capture_status_t packet; - packet.time_boot_ms = time_boot_ms; - packet.image_interval = image_interval; - packet.recording_time_ms = recording_time_ms; - packet.available_capacity = available_capacity; - packet.image_status = image_status; - packet.video_status = video_status; - packet.image_count = image_count; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS, (const char *)&packet, MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS_MIN_LEN, MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS_LEN, MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS_CRC); -#endif -} - -/** - * @brief Send a camera_capture_status message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_camera_capture_status_send_struct(mavlink_channel_t chan, const mavlink_camera_capture_status_t* camera_capture_status) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_camera_capture_status_send(chan, camera_capture_status->time_boot_ms, camera_capture_status->image_status, camera_capture_status->video_status, camera_capture_status->image_interval, camera_capture_status->recording_time_ms, camera_capture_status->available_capacity, camera_capture_status->image_count); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS, (const char *)camera_capture_status, MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS_MIN_LEN, MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS_LEN, MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS_CRC); -#endif -} - -#if MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_camera_capture_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t image_status, uint8_t video_status, float image_interval, uint32_t recording_time_ms, float available_capacity, int32_t image_count) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, image_interval); - _mav_put_uint32_t(buf, 8, recording_time_ms); - _mav_put_float(buf, 12, available_capacity); - _mav_put_uint8_t(buf, 16, image_status); - _mav_put_uint8_t(buf, 17, video_status); - _mav_put_int32_t(buf, 18, image_count); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS, buf, MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS_MIN_LEN, MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS_LEN, MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS_CRC); -#else - mavlink_camera_capture_status_t *packet = (mavlink_camera_capture_status_t *)msgbuf; - packet->time_boot_ms = time_boot_ms; - packet->image_interval = image_interval; - packet->recording_time_ms = recording_time_ms; - packet->available_capacity = available_capacity; - packet->image_status = image_status; - packet->video_status = video_status; - packet->image_count = image_count; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS, (const char *)packet, MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS_MIN_LEN, MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS_LEN, MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS_CRC); -#endif -} -#endif - -#endif - -// MESSAGE CAMERA_CAPTURE_STATUS UNPACKING - - -/** - * @brief Get field time_boot_ms from camera_capture_status message - * - * @return [ms] Timestamp (time since system boot). - */ -static inline uint32_t mavlink_msg_camera_capture_status_get_time_boot_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field image_status from camera_capture_status message - * - * @return Current status of image capturing (0: idle, 1: capture in progress, 2: interval set but idle, 3: interval set and capture in progress) - */ -static inline uint8_t mavlink_msg_camera_capture_status_get_image_status(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 16); -} - -/** - * @brief Get field video_status from camera_capture_status message - * - * @return Current status of video capturing (0: idle, 1: capture in progress) - */ -static inline uint8_t mavlink_msg_camera_capture_status_get_video_status(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 17); -} - -/** - * @brief Get field image_interval from camera_capture_status message - * - * @return [s] Image capture interval - */ -static inline float mavlink_msg_camera_capture_status_get_image_interval(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 4); -} - -/** - * @brief Get field recording_time_ms from camera_capture_status message - * - * @return [ms] Elapsed time since recording started (0: Not supported/available). A GCS should compute recording time and use non-zero values of this field to correct any discrepancy. - */ -static inline uint32_t mavlink_msg_camera_capture_status_get_recording_time_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 8); -} - -/** - * @brief Get field available_capacity from camera_capture_status message - * - * @return [MiB] Available storage capacity. - */ -static inline float mavlink_msg_camera_capture_status_get_available_capacity(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field image_count from camera_capture_status message - * - * @return Total number of images captured ('forever', or until reset using MAV_CMD_STORAGE_FORMAT). - */ -static inline int32_t mavlink_msg_camera_capture_status_get_image_count(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 18); -} - -/** - * @brief Decode a camera_capture_status message into a struct - * - * @param msg The message to decode - * @param camera_capture_status C-struct to decode the message contents into - */ -static inline void mavlink_msg_camera_capture_status_decode(const mavlink_message_t* msg, mavlink_camera_capture_status_t* camera_capture_status) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - camera_capture_status->time_boot_ms = mavlink_msg_camera_capture_status_get_time_boot_ms(msg); - camera_capture_status->image_interval = mavlink_msg_camera_capture_status_get_image_interval(msg); - camera_capture_status->recording_time_ms = mavlink_msg_camera_capture_status_get_recording_time_ms(msg); - camera_capture_status->available_capacity = mavlink_msg_camera_capture_status_get_available_capacity(msg); - camera_capture_status->image_status = mavlink_msg_camera_capture_status_get_image_status(msg); - camera_capture_status->video_status = mavlink_msg_camera_capture_status_get_video_status(msg); - camera_capture_status->image_count = mavlink_msg_camera_capture_status_get_image_count(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS_LEN? msg->len : MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS_LEN; - memset(camera_capture_status, 0, MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS_LEN); - memcpy(camera_capture_status, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_camera_fov_status.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_camera_fov_status.h deleted file mode 100644 index 8562973f..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_camera_fov_status.h +++ /dev/null @@ -1,430 +0,0 @@ -#pragma once -// MESSAGE CAMERA_FOV_STATUS PACKING - -#define MAVLINK_MSG_ID_CAMERA_FOV_STATUS 271 - - -typedef struct __mavlink_camera_fov_status_t { - uint32_t time_boot_ms; /*< [ms] Timestamp (time since system boot).*/ - int32_t lat_camera; /*< [degE7] Latitude of camera (INT32_MAX if unknown).*/ - int32_t lon_camera; /*< [degE7] Longitude of camera (INT32_MAX if unknown).*/ - int32_t alt_camera; /*< [mm] Altitude (MSL) of camera (INT32_MAX if unknown).*/ - int32_t lat_image; /*< [degE7] Latitude of center of image (INT32_MAX if unknown, INT32_MIN if at infinity, not intersecting with horizon).*/ - int32_t lon_image; /*< [degE7] Longitude of center of image (INT32_MAX if unknown, INT32_MIN if at infinity, not intersecting with horizon).*/ - int32_t alt_image; /*< [mm] Altitude (MSL) of center of image (INT32_MAX if unknown, INT32_MIN if at infinity, not intersecting with horizon).*/ - float q[4]; /*< Quaternion of camera orientation (w, x, y, z order, zero-rotation is 1, 0, 0, 0)*/ - float hfov; /*< [deg] Horizontal field of view (NaN if unknown).*/ - float vfov; /*< [deg] Vertical field of view (NaN if unknown).*/ -} mavlink_camera_fov_status_t; - -#define MAVLINK_MSG_ID_CAMERA_FOV_STATUS_LEN 52 -#define MAVLINK_MSG_ID_CAMERA_FOV_STATUS_MIN_LEN 52 -#define MAVLINK_MSG_ID_271_LEN 52 -#define MAVLINK_MSG_ID_271_MIN_LEN 52 - -#define MAVLINK_MSG_ID_CAMERA_FOV_STATUS_CRC 22 -#define MAVLINK_MSG_ID_271_CRC 22 - -#define MAVLINK_MSG_CAMERA_FOV_STATUS_FIELD_Q_LEN 4 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_CAMERA_FOV_STATUS { \ - 271, \ - "CAMERA_FOV_STATUS", \ - 10, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_camera_fov_status_t, time_boot_ms) }, \ - { "lat_camera", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_camera_fov_status_t, lat_camera) }, \ - { "lon_camera", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_camera_fov_status_t, lon_camera) }, \ - { "alt_camera", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_camera_fov_status_t, alt_camera) }, \ - { "lat_image", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_camera_fov_status_t, lat_image) }, \ - { "lon_image", NULL, MAVLINK_TYPE_INT32_T, 0, 20, offsetof(mavlink_camera_fov_status_t, lon_image) }, \ - { "alt_image", NULL, MAVLINK_TYPE_INT32_T, 0, 24, offsetof(mavlink_camera_fov_status_t, alt_image) }, \ - { "q", NULL, MAVLINK_TYPE_FLOAT, 4, 28, offsetof(mavlink_camera_fov_status_t, q) }, \ - { "hfov", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_camera_fov_status_t, hfov) }, \ - { "vfov", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_camera_fov_status_t, vfov) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_CAMERA_FOV_STATUS { \ - "CAMERA_FOV_STATUS", \ - 10, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_camera_fov_status_t, time_boot_ms) }, \ - { "lat_camera", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_camera_fov_status_t, lat_camera) }, \ - { "lon_camera", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_camera_fov_status_t, lon_camera) }, \ - { "alt_camera", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_camera_fov_status_t, alt_camera) }, \ - { "lat_image", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_camera_fov_status_t, lat_image) }, \ - { "lon_image", NULL, MAVLINK_TYPE_INT32_T, 0, 20, offsetof(mavlink_camera_fov_status_t, lon_image) }, \ - { "alt_image", NULL, MAVLINK_TYPE_INT32_T, 0, 24, offsetof(mavlink_camera_fov_status_t, alt_image) }, \ - { "q", NULL, MAVLINK_TYPE_FLOAT, 4, 28, offsetof(mavlink_camera_fov_status_t, q) }, \ - { "hfov", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_camera_fov_status_t, hfov) }, \ - { "vfov", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_camera_fov_status_t, vfov) }, \ - } \ -} -#endif - -/** - * @brief Pack a camera_fov_status message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param time_boot_ms [ms] Timestamp (time since system boot). - * @param lat_camera [degE7] Latitude of camera (INT32_MAX if unknown). - * @param lon_camera [degE7] Longitude of camera (INT32_MAX if unknown). - * @param alt_camera [mm] Altitude (MSL) of camera (INT32_MAX if unknown). - * @param lat_image [degE7] Latitude of center of image (INT32_MAX if unknown, INT32_MIN if at infinity, not intersecting with horizon). - * @param lon_image [degE7] Longitude of center of image (INT32_MAX if unknown, INT32_MIN if at infinity, not intersecting with horizon). - * @param alt_image [mm] Altitude (MSL) of center of image (INT32_MAX if unknown, INT32_MIN if at infinity, not intersecting with horizon). - * @param q Quaternion of camera orientation (w, x, y, z order, zero-rotation is 1, 0, 0, 0) - * @param hfov [deg] Horizontal field of view (NaN if unknown). - * @param vfov [deg] Vertical field of view (NaN if unknown). - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_camera_fov_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint32_t time_boot_ms, int32_t lat_camera, int32_t lon_camera, int32_t alt_camera, int32_t lat_image, int32_t lon_image, int32_t alt_image, const float *q, float hfov, float vfov) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_CAMERA_FOV_STATUS_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_int32_t(buf, 4, lat_camera); - _mav_put_int32_t(buf, 8, lon_camera); - _mav_put_int32_t(buf, 12, alt_camera); - _mav_put_int32_t(buf, 16, lat_image); - _mav_put_int32_t(buf, 20, lon_image); - _mav_put_int32_t(buf, 24, alt_image); - _mav_put_float(buf, 44, hfov); - _mav_put_float(buf, 48, vfov); - _mav_put_float_array(buf, 28, q, 4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CAMERA_FOV_STATUS_LEN); -#else - mavlink_camera_fov_status_t packet; - packet.time_boot_ms = time_boot_ms; - packet.lat_camera = lat_camera; - packet.lon_camera = lon_camera; - packet.alt_camera = alt_camera; - packet.lat_image = lat_image; - packet.lon_image = lon_image; - packet.alt_image = alt_image; - packet.hfov = hfov; - packet.vfov = vfov; - mav_array_memcpy(packet.q, q, sizeof(float)*4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CAMERA_FOV_STATUS_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_CAMERA_FOV_STATUS; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_CAMERA_FOV_STATUS_MIN_LEN, MAVLINK_MSG_ID_CAMERA_FOV_STATUS_LEN, MAVLINK_MSG_ID_CAMERA_FOV_STATUS_CRC); -} - -/** - * @brief Pack a camera_fov_status message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_boot_ms [ms] Timestamp (time since system boot). - * @param lat_camera [degE7] Latitude of camera (INT32_MAX if unknown). - * @param lon_camera [degE7] Longitude of camera (INT32_MAX if unknown). - * @param alt_camera [mm] Altitude (MSL) of camera (INT32_MAX if unknown). - * @param lat_image [degE7] Latitude of center of image (INT32_MAX if unknown, INT32_MIN if at infinity, not intersecting with horizon). - * @param lon_image [degE7] Longitude of center of image (INT32_MAX if unknown, INT32_MIN if at infinity, not intersecting with horizon). - * @param alt_image [mm] Altitude (MSL) of center of image (INT32_MAX if unknown, INT32_MIN if at infinity, not intersecting with horizon). - * @param q Quaternion of camera orientation (w, x, y, z order, zero-rotation is 1, 0, 0, 0) - * @param hfov [deg] Horizontal field of view (NaN if unknown). - * @param vfov [deg] Vertical field of view (NaN if unknown). - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_camera_fov_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint32_t time_boot_ms,int32_t lat_camera,int32_t lon_camera,int32_t alt_camera,int32_t lat_image,int32_t lon_image,int32_t alt_image,const float *q,float hfov,float vfov) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_CAMERA_FOV_STATUS_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_int32_t(buf, 4, lat_camera); - _mav_put_int32_t(buf, 8, lon_camera); - _mav_put_int32_t(buf, 12, alt_camera); - _mav_put_int32_t(buf, 16, lat_image); - _mav_put_int32_t(buf, 20, lon_image); - _mav_put_int32_t(buf, 24, alt_image); - _mav_put_float(buf, 44, hfov); - _mav_put_float(buf, 48, vfov); - _mav_put_float_array(buf, 28, q, 4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CAMERA_FOV_STATUS_LEN); -#else - mavlink_camera_fov_status_t packet; - packet.time_boot_ms = time_boot_ms; - packet.lat_camera = lat_camera; - packet.lon_camera = lon_camera; - packet.alt_camera = alt_camera; - packet.lat_image = lat_image; - packet.lon_image = lon_image; - packet.alt_image = alt_image; - packet.hfov = hfov; - packet.vfov = vfov; - mav_array_memcpy(packet.q, q, sizeof(float)*4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CAMERA_FOV_STATUS_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_CAMERA_FOV_STATUS; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_CAMERA_FOV_STATUS_MIN_LEN, MAVLINK_MSG_ID_CAMERA_FOV_STATUS_LEN, MAVLINK_MSG_ID_CAMERA_FOV_STATUS_CRC); -} - -/** - * @brief Encode a camera_fov_status struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param camera_fov_status C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_camera_fov_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_camera_fov_status_t* camera_fov_status) -{ - return mavlink_msg_camera_fov_status_pack(system_id, component_id, msg, camera_fov_status->time_boot_ms, camera_fov_status->lat_camera, camera_fov_status->lon_camera, camera_fov_status->alt_camera, camera_fov_status->lat_image, camera_fov_status->lon_image, camera_fov_status->alt_image, camera_fov_status->q, camera_fov_status->hfov, camera_fov_status->vfov); -} - -/** - * @brief Encode a camera_fov_status struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param camera_fov_status C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_camera_fov_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_camera_fov_status_t* camera_fov_status) -{ - return mavlink_msg_camera_fov_status_pack_chan(system_id, component_id, chan, msg, camera_fov_status->time_boot_ms, camera_fov_status->lat_camera, camera_fov_status->lon_camera, camera_fov_status->alt_camera, camera_fov_status->lat_image, camera_fov_status->lon_image, camera_fov_status->alt_image, camera_fov_status->q, camera_fov_status->hfov, camera_fov_status->vfov); -} - -/** - * @brief Send a camera_fov_status message - * @param chan MAVLink channel to send the message - * - * @param time_boot_ms [ms] Timestamp (time since system boot). - * @param lat_camera [degE7] Latitude of camera (INT32_MAX if unknown). - * @param lon_camera [degE7] Longitude of camera (INT32_MAX if unknown). - * @param alt_camera [mm] Altitude (MSL) of camera (INT32_MAX if unknown). - * @param lat_image [degE7] Latitude of center of image (INT32_MAX if unknown, INT32_MIN if at infinity, not intersecting with horizon). - * @param lon_image [degE7] Longitude of center of image (INT32_MAX if unknown, INT32_MIN if at infinity, not intersecting with horizon). - * @param alt_image [mm] Altitude (MSL) of center of image (INT32_MAX if unknown, INT32_MIN if at infinity, not intersecting with horizon). - * @param q Quaternion of camera orientation (w, x, y, z order, zero-rotation is 1, 0, 0, 0) - * @param hfov [deg] Horizontal field of view (NaN if unknown). - * @param vfov [deg] Vertical field of view (NaN if unknown). - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_camera_fov_status_send(mavlink_channel_t chan, uint32_t time_boot_ms, int32_t lat_camera, int32_t lon_camera, int32_t alt_camera, int32_t lat_image, int32_t lon_image, int32_t alt_image, const float *q, float hfov, float vfov) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_CAMERA_FOV_STATUS_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_int32_t(buf, 4, lat_camera); - _mav_put_int32_t(buf, 8, lon_camera); - _mav_put_int32_t(buf, 12, alt_camera); - _mav_put_int32_t(buf, 16, lat_image); - _mav_put_int32_t(buf, 20, lon_image); - _mav_put_int32_t(buf, 24, alt_image); - _mav_put_float(buf, 44, hfov); - _mav_put_float(buf, 48, vfov); - _mav_put_float_array(buf, 28, q, 4); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_FOV_STATUS, buf, MAVLINK_MSG_ID_CAMERA_FOV_STATUS_MIN_LEN, MAVLINK_MSG_ID_CAMERA_FOV_STATUS_LEN, MAVLINK_MSG_ID_CAMERA_FOV_STATUS_CRC); -#else - mavlink_camera_fov_status_t packet; - packet.time_boot_ms = time_boot_ms; - packet.lat_camera = lat_camera; - packet.lon_camera = lon_camera; - packet.alt_camera = alt_camera; - packet.lat_image = lat_image; - packet.lon_image = lon_image; - packet.alt_image = alt_image; - packet.hfov = hfov; - packet.vfov = vfov; - mav_array_memcpy(packet.q, q, sizeof(float)*4); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_FOV_STATUS, (const char *)&packet, MAVLINK_MSG_ID_CAMERA_FOV_STATUS_MIN_LEN, MAVLINK_MSG_ID_CAMERA_FOV_STATUS_LEN, MAVLINK_MSG_ID_CAMERA_FOV_STATUS_CRC); -#endif -} - -/** - * @brief Send a camera_fov_status message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_camera_fov_status_send_struct(mavlink_channel_t chan, const mavlink_camera_fov_status_t* camera_fov_status) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_camera_fov_status_send(chan, camera_fov_status->time_boot_ms, camera_fov_status->lat_camera, camera_fov_status->lon_camera, camera_fov_status->alt_camera, camera_fov_status->lat_image, camera_fov_status->lon_image, camera_fov_status->alt_image, camera_fov_status->q, camera_fov_status->hfov, camera_fov_status->vfov); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_FOV_STATUS, (const char *)camera_fov_status, MAVLINK_MSG_ID_CAMERA_FOV_STATUS_MIN_LEN, MAVLINK_MSG_ID_CAMERA_FOV_STATUS_LEN, MAVLINK_MSG_ID_CAMERA_FOV_STATUS_CRC); -#endif -} - -#if MAVLINK_MSG_ID_CAMERA_FOV_STATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_camera_fov_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, int32_t lat_camera, int32_t lon_camera, int32_t alt_camera, int32_t lat_image, int32_t lon_image, int32_t alt_image, const float *q, float hfov, float vfov) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_int32_t(buf, 4, lat_camera); - _mav_put_int32_t(buf, 8, lon_camera); - _mav_put_int32_t(buf, 12, alt_camera); - _mav_put_int32_t(buf, 16, lat_image); - _mav_put_int32_t(buf, 20, lon_image); - _mav_put_int32_t(buf, 24, alt_image); - _mav_put_float(buf, 44, hfov); - _mav_put_float(buf, 48, vfov); - _mav_put_float_array(buf, 28, q, 4); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_FOV_STATUS, buf, MAVLINK_MSG_ID_CAMERA_FOV_STATUS_MIN_LEN, MAVLINK_MSG_ID_CAMERA_FOV_STATUS_LEN, MAVLINK_MSG_ID_CAMERA_FOV_STATUS_CRC); -#else - mavlink_camera_fov_status_t *packet = (mavlink_camera_fov_status_t *)msgbuf; - packet->time_boot_ms = time_boot_ms; - packet->lat_camera = lat_camera; - packet->lon_camera = lon_camera; - packet->alt_camera = alt_camera; - packet->lat_image = lat_image; - packet->lon_image = lon_image; - packet->alt_image = alt_image; - packet->hfov = hfov; - packet->vfov = vfov; - mav_array_memcpy(packet->q, q, sizeof(float)*4); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_FOV_STATUS, (const char *)packet, MAVLINK_MSG_ID_CAMERA_FOV_STATUS_MIN_LEN, MAVLINK_MSG_ID_CAMERA_FOV_STATUS_LEN, MAVLINK_MSG_ID_CAMERA_FOV_STATUS_CRC); -#endif -} -#endif - -#endif - -// MESSAGE CAMERA_FOV_STATUS UNPACKING - - -/** - * @brief Get field time_boot_ms from camera_fov_status message - * - * @return [ms] Timestamp (time since system boot). - */ -static inline uint32_t mavlink_msg_camera_fov_status_get_time_boot_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field lat_camera from camera_fov_status message - * - * @return [degE7] Latitude of camera (INT32_MAX if unknown). - */ -static inline int32_t mavlink_msg_camera_fov_status_get_lat_camera(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 4); -} - -/** - * @brief Get field lon_camera from camera_fov_status message - * - * @return [degE7] Longitude of camera (INT32_MAX if unknown). - */ -static inline int32_t mavlink_msg_camera_fov_status_get_lon_camera(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 8); -} - -/** - * @brief Get field alt_camera from camera_fov_status message - * - * @return [mm] Altitude (MSL) of camera (INT32_MAX if unknown). - */ -static inline int32_t mavlink_msg_camera_fov_status_get_alt_camera(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 12); -} - -/** - * @brief Get field lat_image from camera_fov_status message - * - * @return [degE7] Latitude of center of image (INT32_MAX if unknown, INT32_MIN if at infinity, not intersecting with horizon). - */ -static inline int32_t mavlink_msg_camera_fov_status_get_lat_image(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 16); -} - -/** - * @brief Get field lon_image from camera_fov_status message - * - * @return [degE7] Longitude of center of image (INT32_MAX if unknown, INT32_MIN if at infinity, not intersecting with horizon). - */ -static inline int32_t mavlink_msg_camera_fov_status_get_lon_image(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 20); -} - -/** - * @brief Get field alt_image from camera_fov_status message - * - * @return [mm] Altitude (MSL) of center of image (INT32_MAX if unknown, INT32_MIN if at infinity, not intersecting with horizon). - */ -static inline int32_t mavlink_msg_camera_fov_status_get_alt_image(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 24); -} - -/** - * @brief Get field q from camera_fov_status message - * - * @return Quaternion of camera orientation (w, x, y, z order, zero-rotation is 1, 0, 0, 0) - */ -static inline uint16_t mavlink_msg_camera_fov_status_get_q(const mavlink_message_t* msg, float *q) -{ - return _MAV_RETURN_float_array(msg, q, 4, 28); -} - -/** - * @brief Get field hfov from camera_fov_status message - * - * @return [deg] Horizontal field of view (NaN if unknown). - */ -static inline float mavlink_msg_camera_fov_status_get_hfov(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 44); -} - -/** - * @brief Get field vfov from camera_fov_status message - * - * @return [deg] Vertical field of view (NaN if unknown). - */ -static inline float mavlink_msg_camera_fov_status_get_vfov(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 48); -} - -/** - * @brief Decode a camera_fov_status message into a struct - * - * @param msg The message to decode - * @param camera_fov_status C-struct to decode the message contents into - */ -static inline void mavlink_msg_camera_fov_status_decode(const mavlink_message_t* msg, mavlink_camera_fov_status_t* camera_fov_status) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - camera_fov_status->time_boot_ms = mavlink_msg_camera_fov_status_get_time_boot_ms(msg); - camera_fov_status->lat_camera = mavlink_msg_camera_fov_status_get_lat_camera(msg); - camera_fov_status->lon_camera = mavlink_msg_camera_fov_status_get_lon_camera(msg); - camera_fov_status->alt_camera = mavlink_msg_camera_fov_status_get_alt_camera(msg); - camera_fov_status->lat_image = mavlink_msg_camera_fov_status_get_lat_image(msg); - camera_fov_status->lon_image = mavlink_msg_camera_fov_status_get_lon_image(msg); - camera_fov_status->alt_image = mavlink_msg_camera_fov_status_get_alt_image(msg); - mavlink_msg_camera_fov_status_get_q(msg, camera_fov_status->q); - camera_fov_status->hfov = mavlink_msg_camera_fov_status_get_hfov(msg); - camera_fov_status->vfov = mavlink_msg_camera_fov_status_get_vfov(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_CAMERA_FOV_STATUS_LEN? msg->len : MAVLINK_MSG_ID_CAMERA_FOV_STATUS_LEN; - memset(camera_fov_status, 0, MAVLINK_MSG_ID_CAMERA_FOV_STATUS_LEN); - memcpy(camera_fov_status, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_camera_image_captured.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_camera_image_captured.h deleted file mode 100644 index 0169740b..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_camera_image_captured.h +++ /dev/null @@ -1,456 +0,0 @@ -#pragma once -// MESSAGE CAMERA_IMAGE_CAPTURED PACKING - -#define MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED 263 - - -typedef struct __mavlink_camera_image_captured_t { - uint64_t time_utc; /*< [us] Timestamp (time since UNIX epoch) in UTC. 0 for unknown.*/ - uint32_t time_boot_ms; /*< [ms] Timestamp (time since system boot).*/ - int32_t lat; /*< [degE7] Latitude where image was taken*/ - int32_t lon; /*< [degE7] Longitude where capture was taken*/ - int32_t alt; /*< [mm] Altitude (MSL) where image was taken*/ - int32_t relative_alt; /*< [mm] Altitude above ground*/ - float q[4]; /*< Quaternion of camera orientation (w, x, y, z order, zero-rotation is 1, 0, 0, 0)*/ - int32_t image_index; /*< Zero based index of this image (i.e. a new image will have index CAMERA_CAPTURE_STATUS.image count -1)*/ - uint8_t camera_id; /*< Deprecated/unused. Component IDs are used to differentiate multiple cameras.*/ - int8_t capture_result; /*< Boolean indicating success (1) or failure (0) while capturing this image.*/ - char file_url[205]; /*< URL of image taken. Either local storage or http://foo.jpg if camera provides an HTTP interface.*/ -} mavlink_camera_image_captured_t; - -#define MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_LEN 255 -#define MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_MIN_LEN 255 -#define MAVLINK_MSG_ID_263_LEN 255 -#define MAVLINK_MSG_ID_263_MIN_LEN 255 - -#define MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_CRC 133 -#define MAVLINK_MSG_ID_263_CRC 133 - -#define MAVLINK_MSG_CAMERA_IMAGE_CAPTURED_FIELD_Q_LEN 4 -#define MAVLINK_MSG_CAMERA_IMAGE_CAPTURED_FIELD_FILE_URL_LEN 205 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_CAMERA_IMAGE_CAPTURED { \ - 263, \ - "CAMERA_IMAGE_CAPTURED", \ - 11, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_camera_image_captured_t, time_boot_ms) }, \ - { "time_utc", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_camera_image_captured_t, time_utc) }, \ - { "camera_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 48, offsetof(mavlink_camera_image_captured_t, camera_id) }, \ - { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_camera_image_captured_t, lat) }, \ - { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_camera_image_captured_t, lon) }, \ - { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 20, offsetof(mavlink_camera_image_captured_t, alt) }, \ - { "relative_alt", NULL, MAVLINK_TYPE_INT32_T, 0, 24, offsetof(mavlink_camera_image_captured_t, relative_alt) }, \ - { "q", NULL, MAVLINK_TYPE_FLOAT, 4, 28, offsetof(mavlink_camera_image_captured_t, q) }, \ - { "image_index", NULL, MAVLINK_TYPE_INT32_T, 0, 44, offsetof(mavlink_camera_image_captured_t, image_index) }, \ - { "capture_result", NULL, MAVLINK_TYPE_INT8_T, 0, 49, offsetof(mavlink_camera_image_captured_t, capture_result) }, \ - { "file_url", NULL, MAVLINK_TYPE_CHAR, 205, 50, offsetof(mavlink_camera_image_captured_t, file_url) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_CAMERA_IMAGE_CAPTURED { \ - "CAMERA_IMAGE_CAPTURED", \ - 11, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_camera_image_captured_t, time_boot_ms) }, \ - { "time_utc", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_camera_image_captured_t, time_utc) }, \ - { "camera_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 48, offsetof(mavlink_camera_image_captured_t, camera_id) }, \ - { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_camera_image_captured_t, lat) }, \ - { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_camera_image_captured_t, lon) }, \ - { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 20, offsetof(mavlink_camera_image_captured_t, alt) }, \ - { "relative_alt", NULL, MAVLINK_TYPE_INT32_T, 0, 24, offsetof(mavlink_camera_image_captured_t, relative_alt) }, \ - { "q", NULL, MAVLINK_TYPE_FLOAT, 4, 28, offsetof(mavlink_camera_image_captured_t, q) }, \ - { "image_index", NULL, MAVLINK_TYPE_INT32_T, 0, 44, offsetof(mavlink_camera_image_captured_t, image_index) }, \ - { "capture_result", NULL, MAVLINK_TYPE_INT8_T, 0, 49, offsetof(mavlink_camera_image_captured_t, capture_result) }, \ - { "file_url", NULL, MAVLINK_TYPE_CHAR, 205, 50, offsetof(mavlink_camera_image_captured_t, file_url) }, \ - } \ -} -#endif - -/** - * @brief Pack a camera_image_captured message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param time_boot_ms [ms] Timestamp (time since system boot). - * @param time_utc [us] Timestamp (time since UNIX epoch) in UTC. 0 for unknown. - * @param camera_id Deprecated/unused. Component IDs are used to differentiate multiple cameras. - * @param lat [degE7] Latitude where image was taken - * @param lon [degE7] Longitude where capture was taken - * @param alt [mm] Altitude (MSL) where image was taken - * @param relative_alt [mm] Altitude above ground - * @param q Quaternion of camera orientation (w, x, y, z order, zero-rotation is 1, 0, 0, 0) - * @param image_index Zero based index of this image (i.e. a new image will have index CAMERA_CAPTURE_STATUS.image count -1) - * @param capture_result Boolean indicating success (1) or failure (0) while capturing this image. - * @param file_url URL of image taken. Either local storage or http://foo.jpg if camera provides an HTTP interface. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_camera_image_captured_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint32_t time_boot_ms, uint64_t time_utc, uint8_t camera_id, int32_t lat, int32_t lon, int32_t alt, int32_t relative_alt, const float *q, int32_t image_index, int8_t capture_result, const char *file_url) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_LEN]; - _mav_put_uint64_t(buf, 0, time_utc); - _mav_put_uint32_t(buf, 8, time_boot_ms); - _mav_put_int32_t(buf, 12, lat); - _mav_put_int32_t(buf, 16, lon); - _mav_put_int32_t(buf, 20, alt); - _mav_put_int32_t(buf, 24, relative_alt); - _mav_put_int32_t(buf, 44, image_index); - _mav_put_uint8_t(buf, 48, camera_id); - _mav_put_int8_t(buf, 49, capture_result); - _mav_put_float_array(buf, 28, q, 4); - _mav_put_char_array(buf, 50, file_url, 205); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_LEN); -#else - mavlink_camera_image_captured_t packet; - packet.time_utc = time_utc; - packet.time_boot_ms = time_boot_ms; - packet.lat = lat; - packet.lon = lon; - packet.alt = alt; - packet.relative_alt = relative_alt; - packet.image_index = image_index; - packet.camera_id = camera_id; - packet.capture_result = capture_result; - mav_array_memcpy(packet.q, q, sizeof(float)*4); - mav_array_memcpy(packet.file_url, file_url, sizeof(char)*205); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_MIN_LEN, MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_LEN, MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_CRC); -} - -/** - * @brief Pack a camera_image_captured message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_boot_ms [ms] Timestamp (time since system boot). - * @param time_utc [us] Timestamp (time since UNIX epoch) in UTC. 0 for unknown. - * @param camera_id Deprecated/unused. Component IDs are used to differentiate multiple cameras. - * @param lat [degE7] Latitude where image was taken - * @param lon [degE7] Longitude where capture was taken - * @param alt [mm] Altitude (MSL) where image was taken - * @param relative_alt [mm] Altitude above ground - * @param q Quaternion of camera orientation (w, x, y, z order, zero-rotation is 1, 0, 0, 0) - * @param image_index Zero based index of this image (i.e. a new image will have index CAMERA_CAPTURE_STATUS.image count -1) - * @param capture_result Boolean indicating success (1) or failure (0) while capturing this image. - * @param file_url URL of image taken. Either local storage or http://foo.jpg if camera provides an HTTP interface. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_camera_image_captured_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint32_t time_boot_ms,uint64_t time_utc,uint8_t camera_id,int32_t lat,int32_t lon,int32_t alt,int32_t relative_alt,const float *q,int32_t image_index,int8_t capture_result,const char *file_url) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_LEN]; - _mav_put_uint64_t(buf, 0, time_utc); - _mav_put_uint32_t(buf, 8, time_boot_ms); - _mav_put_int32_t(buf, 12, lat); - _mav_put_int32_t(buf, 16, lon); - _mav_put_int32_t(buf, 20, alt); - _mav_put_int32_t(buf, 24, relative_alt); - _mav_put_int32_t(buf, 44, image_index); - _mav_put_uint8_t(buf, 48, camera_id); - _mav_put_int8_t(buf, 49, capture_result); - _mav_put_float_array(buf, 28, q, 4); - _mav_put_char_array(buf, 50, file_url, 205); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_LEN); -#else - mavlink_camera_image_captured_t packet; - packet.time_utc = time_utc; - packet.time_boot_ms = time_boot_ms; - packet.lat = lat; - packet.lon = lon; - packet.alt = alt; - packet.relative_alt = relative_alt; - packet.image_index = image_index; - packet.camera_id = camera_id; - packet.capture_result = capture_result; - mav_array_memcpy(packet.q, q, sizeof(float)*4); - mav_array_memcpy(packet.file_url, file_url, sizeof(char)*205); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_MIN_LEN, MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_LEN, MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_CRC); -} - -/** - * @brief Encode a camera_image_captured struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param camera_image_captured C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_camera_image_captured_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_camera_image_captured_t* camera_image_captured) -{ - return mavlink_msg_camera_image_captured_pack(system_id, component_id, msg, camera_image_captured->time_boot_ms, camera_image_captured->time_utc, camera_image_captured->camera_id, camera_image_captured->lat, camera_image_captured->lon, camera_image_captured->alt, camera_image_captured->relative_alt, camera_image_captured->q, camera_image_captured->image_index, camera_image_captured->capture_result, camera_image_captured->file_url); -} - -/** - * @brief Encode a camera_image_captured struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param camera_image_captured C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_camera_image_captured_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_camera_image_captured_t* camera_image_captured) -{ - return mavlink_msg_camera_image_captured_pack_chan(system_id, component_id, chan, msg, camera_image_captured->time_boot_ms, camera_image_captured->time_utc, camera_image_captured->camera_id, camera_image_captured->lat, camera_image_captured->lon, camera_image_captured->alt, camera_image_captured->relative_alt, camera_image_captured->q, camera_image_captured->image_index, camera_image_captured->capture_result, camera_image_captured->file_url); -} - -/** - * @brief Send a camera_image_captured message - * @param chan MAVLink channel to send the message - * - * @param time_boot_ms [ms] Timestamp (time since system boot). - * @param time_utc [us] Timestamp (time since UNIX epoch) in UTC. 0 for unknown. - * @param camera_id Deprecated/unused. Component IDs are used to differentiate multiple cameras. - * @param lat [degE7] Latitude where image was taken - * @param lon [degE7] Longitude where capture was taken - * @param alt [mm] Altitude (MSL) where image was taken - * @param relative_alt [mm] Altitude above ground - * @param q Quaternion of camera orientation (w, x, y, z order, zero-rotation is 1, 0, 0, 0) - * @param image_index Zero based index of this image (i.e. a new image will have index CAMERA_CAPTURE_STATUS.image count -1) - * @param capture_result Boolean indicating success (1) or failure (0) while capturing this image. - * @param file_url URL of image taken. Either local storage or http://foo.jpg if camera provides an HTTP interface. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_camera_image_captured_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint64_t time_utc, uint8_t camera_id, int32_t lat, int32_t lon, int32_t alt, int32_t relative_alt, const float *q, int32_t image_index, int8_t capture_result, const char *file_url) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_LEN]; - _mav_put_uint64_t(buf, 0, time_utc); - _mav_put_uint32_t(buf, 8, time_boot_ms); - _mav_put_int32_t(buf, 12, lat); - _mav_put_int32_t(buf, 16, lon); - _mav_put_int32_t(buf, 20, alt); - _mav_put_int32_t(buf, 24, relative_alt); - _mav_put_int32_t(buf, 44, image_index); - _mav_put_uint8_t(buf, 48, camera_id); - _mav_put_int8_t(buf, 49, capture_result); - _mav_put_float_array(buf, 28, q, 4); - _mav_put_char_array(buf, 50, file_url, 205); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED, buf, MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_MIN_LEN, MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_LEN, MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_CRC); -#else - mavlink_camera_image_captured_t packet; - packet.time_utc = time_utc; - packet.time_boot_ms = time_boot_ms; - packet.lat = lat; - packet.lon = lon; - packet.alt = alt; - packet.relative_alt = relative_alt; - packet.image_index = image_index; - packet.camera_id = camera_id; - packet.capture_result = capture_result; - mav_array_memcpy(packet.q, q, sizeof(float)*4); - mav_array_memcpy(packet.file_url, file_url, sizeof(char)*205); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED, (const char *)&packet, MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_MIN_LEN, MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_LEN, MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_CRC); -#endif -} - -/** - * @brief Send a camera_image_captured message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_camera_image_captured_send_struct(mavlink_channel_t chan, const mavlink_camera_image_captured_t* camera_image_captured) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_camera_image_captured_send(chan, camera_image_captured->time_boot_ms, camera_image_captured->time_utc, camera_image_captured->camera_id, camera_image_captured->lat, camera_image_captured->lon, camera_image_captured->alt, camera_image_captured->relative_alt, camera_image_captured->q, camera_image_captured->image_index, camera_image_captured->capture_result, camera_image_captured->file_url); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED, (const char *)camera_image_captured, MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_MIN_LEN, MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_LEN, MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_CRC); -#endif -} - -#if MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_camera_image_captured_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint64_t time_utc, uint8_t camera_id, int32_t lat, int32_t lon, int32_t alt, int32_t relative_alt, const float *q, int32_t image_index, int8_t capture_result, const char *file_url) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, time_utc); - _mav_put_uint32_t(buf, 8, time_boot_ms); - _mav_put_int32_t(buf, 12, lat); - _mav_put_int32_t(buf, 16, lon); - _mav_put_int32_t(buf, 20, alt); - _mav_put_int32_t(buf, 24, relative_alt); - _mav_put_int32_t(buf, 44, image_index); - _mav_put_uint8_t(buf, 48, camera_id); - _mav_put_int8_t(buf, 49, capture_result); - _mav_put_float_array(buf, 28, q, 4); - _mav_put_char_array(buf, 50, file_url, 205); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED, buf, MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_MIN_LEN, MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_LEN, MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_CRC); -#else - mavlink_camera_image_captured_t *packet = (mavlink_camera_image_captured_t *)msgbuf; - packet->time_utc = time_utc; - packet->time_boot_ms = time_boot_ms; - packet->lat = lat; - packet->lon = lon; - packet->alt = alt; - packet->relative_alt = relative_alt; - packet->image_index = image_index; - packet->camera_id = camera_id; - packet->capture_result = capture_result; - mav_array_memcpy(packet->q, q, sizeof(float)*4); - mav_array_memcpy(packet->file_url, file_url, sizeof(char)*205); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED, (const char *)packet, MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_MIN_LEN, MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_LEN, MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_CRC); -#endif -} -#endif - -#endif - -// MESSAGE CAMERA_IMAGE_CAPTURED UNPACKING - - -/** - * @brief Get field time_boot_ms from camera_image_captured message - * - * @return [ms] Timestamp (time since system boot). - */ -static inline uint32_t mavlink_msg_camera_image_captured_get_time_boot_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 8); -} - -/** - * @brief Get field time_utc from camera_image_captured message - * - * @return [us] Timestamp (time since UNIX epoch) in UTC. 0 for unknown. - */ -static inline uint64_t mavlink_msg_camera_image_captured_get_time_utc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field camera_id from camera_image_captured message - * - * @return Deprecated/unused. Component IDs are used to differentiate multiple cameras. - */ -static inline uint8_t mavlink_msg_camera_image_captured_get_camera_id(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 48); -} - -/** - * @brief Get field lat from camera_image_captured message - * - * @return [degE7] Latitude where image was taken - */ -static inline int32_t mavlink_msg_camera_image_captured_get_lat(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 12); -} - -/** - * @brief Get field lon from camera_image_captured message - * - * @return [degE7] Longitude where capture was taken - */ -static inline int32_t mavlink_msg_camera_image_captured_get_lon(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 16); -} - -/** - * @brief Get field alt from camera_image_captured message - * - * @return [mm] Altitude (MSL) where image was taken - */ -static inline int32_t mavlink_msg_camera_image_captured_get_alt(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 20); -} - -/** - * @brief Get field relative_alt from camera_image_captured message - * - * @return [mm] Altitude above ground - */ -static inline int32_t mavlink_msg_camera_image_captured_get_relative_alt(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 24); -} - -/** - * @brief Get field q from camera_image_captured message - * - * @return Quaternion of camera orientation (w, x, y, z order, zero-rotation is 1, 0, 0, 0) - */ -static inline uint16_t mavlink_msg_camera_image_captured_get_q(const mavlink_message_t* msg, float *q) -{ - return _MAV_RETURN_float_array(msg, q, 4, 28); -} - -/** - * @brief Get field image_index from camera_image_captured message - * - * @return Zero based index of this image (i.e. a new image will have index CAMERA_CAPTURE_STATUS.image count -1) - */ -static inline int32_t mavlink_msg_camera_image_captured_get_image_index(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 44); -} - -/** - * @brief Get field capture_result from camera_image_captured message - * - * @return Boolean indicating success (1) or failure (0) while capturing this image. - */ -static inline int8_t mavlink_msg_camera_image_captured_get_capture_result(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int8_t(msg, 49); -} - -/** - * @brief Get field file_url from camera_image_captured message - * - * @return URL of image taken. Either local storage or http://foo.jpg if camera provides an HTTP interface. - */ -static inline uint16_t mavlink_msg_camera_image_captured_get_file_url(const mavlink_message_t* msg, char *file_url) -{ - return _MAV_RETURN_char_array(msg, file_url, 205, 50); -} - -/** - * @brief Decode a camera_image_captured message into a struct - * - * @param msg The message to decode - * @param camera_image_captured C-struct to decode the message contents into - */ -static inline void mavlink_msg_camera_image_captured_decode(const mavlink_message_t* msg, mavlink_camera_image_captured_t* camera_image_captured) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - camera_image_captured->time_utc = mavlink_msg_camera_image_captured_get_time_utc(msg); - camera_image_captured->time_boot_ms = mavlink_msg_camera_image_captured_get_time_boot_ms(msg); - camera_image_captured->lat = mavlink_msg_camera_image_captured_get_lat(msg); - camera_image_captured->lon = mavlink_msg_camera_image_captured_get_lon(msg); - camera_image_captured->alt = mavlink_msg_camera_image_captured_get_alt(msg); - camera_image_captured->relative_alt = mavlink_msg_camera_image_captured_get_relative_alt(msg); - mavlink_msg_camera_image_captured_get_q(msg, camera_image_captured->q); - camera_image_captured->image_index = mavlink_msg_camera_image_captured_get_image_index(msg); - camera_image_captured->camera_id = mavlink_msg_camera_image_captured_get_camera_id(msg); - camera_image_captured->capture_result = mavlink_msg_camera_image_captured_get_capture_result(msg); - mavlink_msg_camera_image_captured_get_file_url(msg, camera_image_captured->file_url); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_LEN? msg->len : MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_LEN; - memset(camera_image_captured, 0, MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_LEN); - memcpy(camera_image_captured, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_camera_information.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_camera_information.h deleted file mode 100644 index 1b1e4458..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_camera_information.h +++ /dev/null @@ -1,532 +0,0 @@ -#pragma once -// MESSAGE CAMERA_INFORMATION PACKING - -#define MAVLINK_MSG_ID_CAMERA_INFORMATION 259 - - -typedef struct __mavlink_camera_information_t { - uint32_t time_boot_ms; /*< [ms] Timestamp (time since system boot).*/ - uint32_t firmware_version; /*< Version of the camera firmware, encoded as: (Dev & 0xff) << 24 | (Patch & 0xff) << 16 | (Minor & 0xff) << 8 | (Major & 0xff). Use 0 if not known.*/ - float focal_length; /*< [mm] Focal length. Use NaN if not known.*/ - float sensor_size_h; /*< [mm] Image sensor size horizontal. Use NaN if not known.*/ - float sensor_size_v; /*< [mm] Image sensor size vertical. Use NaN if not known.*/ - uint32_t flags; /*< Bitmap of camera capability flags.*/ - uint16_t resolution_h; /*< [pix] Horizontal image resolution. Use 0 if not known.*/ - uint16_t resolution_v; /*< [pix] Vertical image resolution. Use 0 if not known.*/ - uint16_t cam_definition_version; /*< Camera definition version (iteration). Use 0 if not known.*/ - uint8_t vendor_name[32]; /*< Name of the camera vendor*/ - uint8_t model_name[32]; /*< Name of the camera model*/ - uint8_t lens_id; /*< Reserved for a lens ID. Use 0 if not known.*/ - char cam_definition_uri[140]; /*< Camera definition URI (if any, otherwise only basic functions will be available). HTTP- (http://) and MAVLink FTP- (mavlinkftp://) formatted URIs are allowed (and both must be supported by any GCS that implements the Camera Protocol). The definition file may be xz compressed, which will be indicated by the file extension .xml.xz (a GCS that implements the protocol must support decompressing the file). The string needs to be zero terminated. Use a zero-length string if not known.*/ - uint8_t gimbal_device_id; /*< Gimbal id of a gimbal associated with this camera. This is the component id of the gimbal device, or 1-6 for non mavlink gimbals. Use 0 if no gimbal is associated with the camera.*/ -} mavlink_camera_information_t; - -#define MAVLINK_MSG_ID_CAMERA_INFORMATION_LEN 236 -#define MAVLINK_MSG_ID_CAMERA_INFORMATION_MIN_LEN 235 -#define MAVLINK_MSG_ID_259_LEN 236 -#define MAVLINK_MSG_ID_259_MIN_LEN 235 - -#define MAVLINK_MSG_ID_CAMERA_INFORMATION_CRC 92 -#define MAVLINK_MSG_ID_259_CRC 92 - -#define MAVLINK_MSG_CAMERA_INFORMATION_FIELD_VENDOR_NAME_LEN 32 -#define MAVLINK_MSG_CAMERA_INFORMATION_FIELD_MODEL_NAME_LEN 32 -#define MAVLINK_MSG_CAMERA_INFORMATION_FIELD_CAM_DEFINITION_URI_LEN 140 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_CAMERA_INFORMATION { \ - 259, \ - "CAMERA_INFORMATION", \ - 14, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_camera_information_t, time_boot_ms) }, \ - { "vendor_name", NULL, MAVLINK_TYPE_UINT8_T, 32, 30, offsetof(mavlink_camera_information_t, vendor_name) }, \ - { "model_name", NULL, MAVLINK_TYPE_UINT8_T, 32, 62, offsetof(mavlink_camera_information_t, model_name) }, \ - { "firmware_version", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_camera_information_t, firmware_version) }, \ - { "focal_length", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_camera_information_t, focal_length) }, \ - { "sensor_size_h", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_camera_information_t, sensor_size_h) }, \ - { "sensor_size_v", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_camera_information_t, sensor_size_v) }, \ - { "resolution_h", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_camera_information_t, resolution_h) }, \ - { "resolution_v", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_camera_information_t, resolution_v) }, \ - { "lens_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 94, offsetof(mavlink_camera_information_t, lens_id) }, \ - { "flags", NULL, MAVLINK_TYPE_UINT32_T, 0, 20, offsetof(mavlink_camera_information_t, flags) }, \ - { "cam_definition_version", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_camera_information_t, cam_definition_version) }, \ - { "cam_definition_uri", NULL, MAVLINK_TYPE_CHAR, 140, 95, offsetof(mavlink_camera_information_t, cam_definition_uri) }, \ - { "gimbal_device_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 235, offsetof(mavlink_camera_information_t, gimbal_device_id) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_CAMERA_INFORMATION { \ - "CAMERA_INFORMATION", \ - 14, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_camera_information_t, time_boot_ms) }, \ - { "vendor_name", NULL, MAVLINK_TYPE_UINT8_T, 32, 30, offsetof(mavlink_camera_information_t, vendor_name) }, \ - { "model_name", NULL, MAVLINK_TYPE_UINT8_T, 32, 62, offsetof(mavlink_camera_information_t, model_name) }, \ - { "firmware_version", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_camera_information_t, firmware_version) }, \ - { "focal_length", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_camera_information_t, focal_length) }, \ - { "sensor_size_h", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_camera_information_t, sensor_size_h) }, \ - { "sensor_size_v", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_camera_information_t, sensor_size_v) }, \ - { "resolution_h", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_camera_information_t, resolution_h) }, \ - { "resolution_v", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_camera_information_t, resolution_v) }, \ - { "lens_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 94, offsetof(mavlink_camera_information_t, lens_id) }, \ - { "flags", NULL, MAVLINK_TYPE_UINT32_T, 0, 20, offsetof(mavlink_camera_information_t, flags) }, \ - { "cam_definition_version", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_camera_information_t, cam_definition_version) }, \ - { "cam_definition_uri", NULL, MAVLINK_TYPE_CHAR, 140, 95, offsetof(mavlink_camera_information_t, cam_definition_uri) }, \ - { "gimbal_device_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 235, offsetof(mavlink_camera_information_t, gimbal_device_id) }, \ - } \ -} -#endif - -/** - * @brief Pack a camera_information message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param time_boot_ms [ms] Timestamp (time since system boot). - * @param vendor_name Name of the camera vendor - * @param model_name Name of the camera model - * @param firmware_version Version of the camera firmware, encoded as: (Dev & 0xff) << 24 | (Patch & 0xff) << 16 | (Minor & 0xff) << 8 | (Major & 0xff). Use 0 if not known. - * @param focal_length [mm] Focal length. Use NaN if not known. - * @param sensor_size_h [mm] Image sensor size horizontal. Use NaN if not known. - * @param sensor_size_v [mm] Image sensor size vertical. Use NaN if not known. - * @param resolution_h [pix] Horizontal image resolution. Use 0 if not known. - * @param resolution_v [pix] Vertical image resolution. Use 0 if not known. - * @param lens_id Reserved for a lens ID. Use 0 if not known. - * @param flags Bitmap of camera capability flags. - * @param cam_definition_version Camera definition version (iteration). Use 0 if not known. - * @param cam_definition_uri Camera definition URI (if any, otherwise only basic functions will be available). HTTP- (http://) and MAVLink FTP- (mavlinkftp://) formatted URIs are allowed (and both must be supported by any GCS that implements the Camera Protocol). The definition file may be xz compressed, which will be indicated by the file extension .xml.xz (a GCS that implements the protocol must support decompressing the file). The string needs to be zero terminated. Use a zero-length string if not known. - * @param gimbal_device_id Gimbal id of a gimbal associated with this camera. This is the component id of the gimbal device, or 1-6 for non mavlink gimbals. Use 0 if no gimbal is associated with the camera. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_camera_information_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint32_t time_boot_ms, const uint8_t *vendor_name, const uint8_t *model_name, uint32_t firmware_version, float focal_length, float sensor_size_h, float sensor_size_v, uint16_t resolution_h, uint16_t resolution_v, uint8_t lens_id, uint32_t flags, uint16_t cam_definition_version, const char *cam_definition_uri, uint8_t gimbal_device_id) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_CAMERA_INFORMATION_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_uint32_t(buf, 4, firmware_version); - _mav_put_float(buf, 8, focal_length); - _mav_put_float(buf, 12, sensor_size_h); - _mav_put_float(buf, 16, sensor_size_v); - _mav_put_uint32_t(buf, 20, flags); - _mav_put_uint16_t(buf, 24, resolution_h); - _mav_put_uint16_t(buf, 26, resolution_v); - _mav_put_uint16_t(buf, 28, cam_definition_version); - _mav_put_uint8_t(buf, 94, lens_id); - _mav_put_uint8_t(buf, 235, gimbal_device_id); - _mav_put_uint8_t_array(buf, 30, vendor_name, 32); - _mav_put_uint8_t_array(buf, 62, model_name, 32); - _mav_put_char_array(buf, 95, cam_definition_uri, 140); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CAMERA_INFORMATION_LEN); -#else - mavlink_camera_information_t packet; - packet.time_boot_ms = time_boot_ms; - packet.firmware_version = firmware_version; - packet.focal_length = focal_length; - packet.sensor_size_h = sensor_size_h; - packet.sensor_size_v = sensor_size_v; - packet.flags = flags; - packet.resolution_h = resolution_h; - packet.resolution_v = resolution_v; - packet.cam_definition_version = cam_definition_version; - packet.lens_id = lens_id; - packet.gimbal_device_id = gimbal_device_id; - mav_array_memcpy(packet.vendor_name, vendor_name, sizeof(uint8_t)*32); - mav_array_memcpy(packet.model_name, model_name, sizeof(uint8_t)*32); - mav_array_memcpy(packet.cam_definition_uri, cam_definition_uri, sizeof(char)*140); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CAMERA_INFORMATION_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_CAMERA_INFORMATION; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_CAMERA_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_CAMERA_INFORMATION_LEN, MAVLINK_MSG_ID_CAMERA_INFORMATION_CRC); -} - -/** - * @brief Pack a camera_information message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_boot_ms [ms] Timestamp (time since system boot). - * @param vendor_name Name of the camera vendor - * @param model_name Name of the camera model - * @param firmware_version Version of the camera firmware, encoded as: (Dev & 0xff) << 24 | (Patch & 0xff) << 16 | (Minor & 0xff) << 8 | (Major & 0xff). Use 0 if not known. - * @param focal_length [mm] Focal length. Use NaN if not known. - * @param sensor_size_h [mm] Image sensor size horizontal. Use NaN if not known. - * @param sensor_size_v [mm] Image sensor size vertical. Use NaN if not known. - * @param resolution_h [pix] Horizontal image resolution. Use 0 if not known. - * @param resolution_v [pix] Vertical image resolution. Use 0 if not known. - * @param lens_id Reserved for a lens ID. Use 0 if not known. - * @param flags Bitmap of camera capability flags. - * @param cam_definition_version Camera definition version (iteration). Use 0 if not known. - * @param cam_definition_uri Camera definition URI (if any, otherwise only basic functions will be available). HTTP- (http://) and MAVLink FTP- (mavlinkftp://) formatted URIs are allowed (and both must be supported by any GCS that implements the Camera Protocol). The definition file may be xz compressed, which will be indicated by the file extension .xml.xz (a GCS that implements the protocol must support decompressing the file). The string needs to be zero terminated. Use a zero-length string if not known. - * @param gimbal_device_id Gimbal id of a gimbal associated with this camera. This is the component id of the gimbal device, or 1-6 for non mavlink gimbals. Use 0 if no gimbal is associated with the camera. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_camera_information_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint32_t time_boot_ms,const uint8_t *vendor_name,const uint8_t *model_name,uint32_t firmware_version,float focal_length,float sensor_size_h,float sensor_size_v,uint16_t resolution_h,uint16_t resolution_v,uint8_t lens_id,uint32_t flags,uint16_t cam_definition_version,const char *cam_definition_uri,uint8_t gimbal_device_id) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_CAMERA_INFORMATION_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_uint32_t(buf, 4, firmware_version); - _mav_put_float(buf, 8, focal_length); - _mav_put_float(buf, 12, sensor_size_h); - _mav_put_float(buf, 16, sensor_size_v); - _mav_put_uint32_t(buf, 20, flags); - _mav_put_uint16_t(buf, 24, resolution_h); - _mav_put_uint16_t(buf, 26, resolution_v); - _mav_put_uint16_t(buf, 28, cam_definition_version); - _mav_put_uint8_t(buf, 94, lens_id); - _mav_put_uint8_t(buf, 235, gimbal_device_id); - _mav_put_uint8_t_array(buf, 30, vendor_name, 32); - _mav_put_uint8_t_array(buf, 62, model_name, 32); - _mav_put_char_array(buf, 95, cam_definition_uri, 140); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CAMERA_INFORMATION_LEN); -#else - mavlink_camera_information_t packet; - packet.time_boot_ms = time_boot_ms; - packet.firmware_version = firmware_version; - packet.focal_length = focal_length; - packet.sensor_size_h = sensor_size_h; - packet.sensor_size_v = sensor_size_v; - packet.flags = flags; - packet.resolution_h = resolution_h; - packet.resolution_v = resolution_v; - packet.cam_definition_version = cam_definition_version; - packet.lens_id = lens_id; - packet.gimbal_device_id = gimbal_device_id; - mav_array_memcpy(packet.vendor_name, vendor_name, sizeof(uint8_t)*32); - mav_array_memcpy(packet.model_name, model_name, sizeof(uint8_t)*32); - mav_array_memcpy(packet.cam_definition_uri, cam_definition_uri, sizeof(char)*140); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CAMERA_INFORMATION_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_CAMERA_INFORMATION; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_CAMERA_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_CAMERA_INFORMATION_LEN, MAVLINK_MSG_ID_CAMERA_INFORMATION_CRC); -} - -/** - * @brief Encode a camera_information struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param camera_information C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_camera_information_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_camera_information_t* camera_information) -{ - return mavlink_msg_camera_information_pack(system_id, component_id, msg, camera_information->time_boot_ms, camera_information->vendor_name, camera_information->model_name, camera_information->firmware_version, camera_information->focal_length, camera_information->sensor_size_h, camera_information->sensor_size_v, camera_information->resolution_h, camera_information->resolution_v, camera_information->lens_id, camera_information->flags, camera_information->cam_definition_version, camera_information->cam_definition_uri, camera_information->gimbal_device_id); -} - -/** - * @brief Encode a camera_information struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param camera_information C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_camera_information_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_camera_information_t* camera_information) -{ - return mavlink_msg_camera_information_pack_chan(system_id, component_id, chan, msg, camera_information->time_boot_ms, camera_information->vendor_name, camera_information->model_name, camera_information->firmware_version, camera_information->focal_length, camera_information->sensor_size_h, camera_information->sensor_size_v, camera_information->resolution_h, camera_information->resolution_v, camera_information->lens_id, camera_information->flags, camera_information->cam_definition_version, camera_information->cam_definition_uri, camera_information->gimbal_device_id); -} - -/** - * @brief Send a camera_information message - * @param chan MAVLink channel to send the message - * - * @param time_boot_ms [ms] Timestamp (time since system boot). - * @param vendor_name Name of the camera vendor - * @param model_name Name of the camera model - * @param firmware_version Version of the camera firmware, encoded as: (Dev & 0xff) << 24 | (Patch & 0xff) << 16 | (Minor & 0xff) << 8 | (Major & 0xff). Use 0 if not known. - * @param focal_length [mm] Focal length. Use NaN if not known. - * @param sensor_size_h [mm] Image sensor size horizontal. Use NaN if not known. - * @param sensor_size_v [mm] Image sensor size vertical. Use NaN if not known. - * @param resolution_h [pix] Horizontal image resolution. Use 0 if not known. - * @param resolution_v [pix] Vertical image resolution. Use 0 if not known. - * @param lens_id Reserved for a lens ID. Use 0 if not known. - * @param flags Bitmap of camera capability flags. - * @param cam_definition_version Camera definition version (iteration). Use 0 if not known. - * @param cam_definition_uri Camera definition URI (if any, otherwise only basic functions will be available). HTTP- (http://) and MAVLink FTP- (mavlinkftp://) formatted URIs are allowed (and both must be supported by any GCS that implements the Camera Protocol). The definition file may be xz compressed, which will be indicated by the file extension .xml.xz (a GCS that implements the protocol must support decompressing the file). The string needs to be zero terminated. Use a zero-length string if not known. - * @param gimbal_device_id Gimbal id of a gimbal associated with this camera. This is the component id of the gimbal device, or 1-6 for non mavlink gimbals. Use 0 if no gimbal is associated with the camera. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_camera_information_send(mavlink_channel_t chan, uint32_t time_boot_ms, const uint8_t *vendor_name, const uint8_t *model_name, uint32_t firmware_version, float focal_length, float sensor_size_h, float sensor_size_v, uint16_t resolution_h, uint16_t resolution_v, uint8_t lens_id, uint32_t flags, uint16_t cam_definition_version, const char *cam_definition_uri, uint8_t gimbal_device_id) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_CAMERA_INFORMATION_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_uint32_t(buf, 4, firmware_version); - _mav_put_float(buf, 8, focal_length); - _mav_put_float(buf, 12, sensor_size_h); - _mav_put_float(buf, 16, sensor_size_v); - _mav_put_uint32_t(buf, 20, flags); - _mav_put_uint16_t(buf, 24, resolution_h); - _mav_put_uint16_t(buf, 26, resolution_v); - _mav_put_uint16_t(buf, 28, cam_definition_version); - _mav_put_uint8_t(buf, 94, lens_id); - _mav_put_uint8_t(buf, 235, gimbal_device_id); - _mav_put_uint8_t_array(buf, 30, vendor_name, 32); - _mav_put_uint8_t_array(buf, 62, model_name, 32); - _mav_put_char_array(buf, 95, cam_definition_uri, 140); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_INFORMATION, buf, MAVLINK_MSG_ID_CAMERA_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_CAMERA_INFORMATION_LEN, MAVLINK_MSG_ID_CAMERA_INFORMATION_CRC); -#else - mavlink_camera_information_t packet; - packet.time_boot_ms = time_boot_ms; - packet.firmware_version = firmware_version; - packet.focal_length = focal_length; - packet.sensor_size_h = sensor_size_h; - packet.sensor_size_v = sensor_size_v; - packet.flags = flags; - packet.resolution_h = resolution_h; - packet.resolution_v = resolution_v; - packet.cam_definition_version = cam_definition_version; - packet.lens_id = lens_id; - packet.gimbal_device_id = gimbal_device_id; - mav_array_memcpy(packet.vendor_name, vendor_name, sizeof(uint8_t)*32); - mav_array_memcpy(packet.model_name, model_name, sizeof(uint8_t)*32); - mav_array_memcpy(packet.cam_definition_uri, cam_definition_uri, sizeof(char)*140); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_INFORMATION, (const char *)&packet, MAVLINK_MSG_ID_CAMERA_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_CAMERA_INFORMATION_LEN, MAVLINK_MSG_ID_CAMERA_INFORMATION_CRC); -#endif -} - -/** - * @brief Send a camera_information message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_camera_information_send_struct(mavlink_channel_t chan, const mavlink_camera_information_t* camera_information) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_camera_information_send(chan, camera_information->time_boot_ms, camera_information->vendor_name, camera_information->model_name, camera_information->firmware_version, camera_information->focal_length, camera_information->sensor_size_h, camera_information->sensor_size_v, camera_information->resolution_h, camera_information->resolution_v, camera_information->lens_id, camera_information->flags, camera_information->cam_definition_version, camera_information->cam_definition_uri, camera_information->gimbal_device_id); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_INFORMATION, (const char *)camera_information, MAVLINK_MSG_ID_CAMERA_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_CAMERA_INFORMATION_LEN, MAVLINK_MSG_ID_CAMERA_INFORMATION_CRC); -#endif -} - -#if MAVLINK_MSG_ID_CAMERA_INFORMATION_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_camera_information_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, const uint8_t *vendor_name, const uint8_t *model_name, uint32_t firmware_version, float focal_length, float sensor_size_h, float sensor_size_v, uint16_t resolution_h, uint16_t resolution_v, uint8_t lens_id, uint32_t flags, uint16_t cam_definition_version, const char *cam_definition_uri, uint8_t gimbal_device_id) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_uint32_t(buf, 4, firmware_version); - _mav_put_float(buf, 8, focal_length); - _mav_put_float(buf, 12, sensor_size_h); - _mav_put_float(buf, 16, sensor_size_v); - _mav_put_uint32_t(buf, 20, flags); - _mav_put_uint16_t(buf, 24, resolution_h); - _mav_put_uint16_t(buf, 26, resolution_v); - _mav_put_uint16_t(buf, 28, cam_definition_version); - _mav_put_uint8_t(buf, 94, lens_id); - _mav_put_uint8_t(buf, 235, gimbal_device_id); - _mav_put_uint8_t_array(buf, 30, vendor_name, 32); - _mav_put_uint8_t_array(buf, 62, model_name, 32); - _mav_put_char_array(buf, 95, cam_definition_uri, 140); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_INFORMATION, buf, MAVLINK_MSG_ID_CAMERA_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_CAMERA_INFORMATION_LEN, MAVLINK_MSG_ID_CAMERA_INFORMATION_CRC); -#else - mavlink_camera_information_t *packet = (mavlink_camera_information_t *)msgbuf; - packet->time_boot_ms = time_boot_ms; - packet->firmware_version = firmware_version; - packet->focal_length = focal_length; - packet->sensor_size_h = sensor_size_h; - packet->sensor_size_v = sensor_size_v; - packet->flags = flags; - packet->resolution_h = resolution_h; - packet->resolution_v = resolution_v; - packet->cam_definition_version = cam_definition_version; - packet->lens_id = lens_id; - packet->gimbal_device_id = gimbal_device_id; - mav_array_memcpy(packet->vendor_name, vendor_name, sizeof(uint8_t)*32); - mav_array_memcpy(packet->model_name, model_name, sizeof(uint8_t)*32); - mav_array_memcpy(packet->cam_definition_uri, cam_definition_uri, sizeof(char)*140); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_INFORMATION, (const char *)packet, MAVLINK_MSG_ID_CAMERA_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_CAMERA_INFORMATION_LEN, MAVLINK_MSG_ID_CAMERA_INFORMATION_CRC); -#endif -} -#endif - -#endif - -// MESSAGE CAMERA_INFORMATION UNPACKING - - -/** - * @brief Get field time_boot_ms from camera_information message - * - * @return [ms] Timestamp (time since system boot). - */ -static inline uint32_t mavlink_msg_camera_information_get_time_boot_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field vendor_name from camera_information message - * - * @return Name of the camera vendor - */ -static inline uint16_t mavlink_msg_camera_information_get_vendor_name(const mavlink_message_t* msg, uint8_t *vendor_name) -{ - return _MAV_RETURN_uint8_t_array(msg, vendor_name, 32, 30); -} - -/** - * @brief Get field model_name from camera_information message - * - * @return Name of the camera model - */ -static inline uint16_t mavlink_msg_camera_information_get_model_name(const mavlink_message_t* msg, uint8_t *model_name) -{ - return _MAV_RETURN_uint8_t_array(msg, model_name, 32, 62); -} - -/** - * @brief Get field firmware_version from camera_information message - * - * @return Version of the camera firmware, encoded as: (Dev & 0xff) << 24 | (Patch & 0xff) << 16 | (Minor & 0xff) << 8 | (Major & 0xff). Use 0 if not known. - */ -static inline uint32_t mavlink_msg_camera_information_get_firmware_version(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 4); -} - -/** - * @brief Get field focal_length from camera_information message - * - * @return [mm] Focal length. Use NaN if not known. - */ -static inline float mavlink_msg_camera_information_get_focal_length(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field sensor_size_h from camera_information message - * - * @return [mm] Image sensor size horizontal. Use NaN if not known. - */ -static inline float mavlink_msg_camera_information_get_sensor_size_h(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field sensor_size_v from camera_information message - * - * @return [mm] Image sensor size vertical. Use NaN if not known. - */ -static inline float mavlink_msg_camera_information_get_sensor_size_v(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field resolution_h from camera_information message - * - * @return [pix] Horizontal image resolution. Use 0 if not known. - */ -static inline uint16_t mavlink_msg_camera_information_get_resolution_h(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 24); -} - -/** - * @brief Get field resolution_v from camera_information message - * - * @return [pix] Vertical image resolution. Use 0 if not known. - */ -static inline uint16_t mavlink_msg_camera_information_get_resolution_v(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 26); -} - -/** - * @brief Get field lens_id from camera_information message - * - * @return Reserved for a lens ID. Use 0 if not known. - */ -static inline uint8_t mavlink_msg_camera_information_get_lens_id(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 94); -} - -/** - * @brief Get field flags from camera_information message - * - * @return Bitmap of camera capability flags. - */ -static inline uint32_t mavlink_msg_camera_information_get_flags(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 20); -} - -/** - * @brief Get field cam_definition_version from camera_information message - * - * @return Camera definition version (iteration). Use 0 if not known. - */ -static inline uint16_t mavlink_msg_camera_information_get_cam_definition_version(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 28); -} - -/** - * @brief Get field cam_definition_uri from camera_information message - * - * @return Camera definition URI (if any, otherwise only basic functions will be available). HTTP- (http://) and MAVLink FTP- (mavlinkftp://) formatted URIs are allowed (and both must be supported by any GCS that implements the Camera Protocol). The definition file may be xz compressed, which will be indicated by the file extension .xml.xz (a GCS that implements the protocol must support decompressing the file). The string needs to be zero terminated. Use a zero-length string if not known. - */ -static inline uint16_t mavlink_msg_camera_information_get_cam_definition_uri(const mavlink_message_t* msg, char *cam_definition_uri) -{ - return _MAV_RETURN_char_array(msg, cam_definition_uri, 140, 95); -} - -/** - * @brief Get field gimbal_device_id from camera_information message - * - * @return Gimbal id of a gimbal associated with this camera. This is the component id of the gimbal device, or 1-6 for non mavlink gimbals. Use 0 if no gimbal is associated with the camera. - */ -static inline uint8_t mavlink_msg_camera_information_get_gimbal_device_id(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 235); -} - -/** - * @brief Decode a camera_information message into a struct - * - * @param msg The message to decode - * @param camera_information C-struct to decode the message contents into - */ -static inline void mavlink_msg_camera_information_decode(const mavlink_message_t* msg, mavlink_camera_information_t* camera_information) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - camera_information->time_boot_ms = mavlink_msg_camera_information_get_time_boot_ms(msg); - camera_information->firmware_version = mavlink_msg_camera_information_get_firmware_version(msg); - camera_information->focal_length = mavlink_msg_camera_information_get_focal_length(msg); - camera_information->sensor_size_h = mavlink_msg_camera_information_get_sensor_size_h(msg); - camera_information->sensor_size_v = mavlink_msg_camera_information_get_sensor_size_v(msg); - camera_information->flags = mavlink_msg_camera_information_get_flags(msg); - camera_information->resolution_h = mavlink_msg_camera_information_get_resolution_h(msg); - camera_information->resolution_v = mavlink_msg_camera_information_get_resolution_v(msg); - camera_information->cam_definition_version = mavlink_msg_camera_information_get_cam_definition_version(msg); - mavlink_msg_camera_information_get_vendor_name(msg, camera_information->vendor_name); - mavlink_msg_camera_information_get_model_name(msg, camera_information->model_name); - camera_information->lens_id = mavlink_msg_camera_information_get_lens_id(msg); - mavlink_msg_camera_information_get_cam_definition_uri(msg, camera_information->cam_definition_uri); - camera_information->gimbal_device_id = mavlink_msg_camera_information_get_gimbal_device_id(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_CAMERA_INFORMATION_LEN? msg->len : MAVLINK_MSG_ID_CAMERA_INFORMATION_LEN; - memset(camera_information, 0, MAVLINK_MSG_ID_CAMERA_INFORMATION_LEN); - memcpy(camera_information, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_camera_settings.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_camera_settings.h deleted file mode 100644 index 9ccba6eb..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_camera_settings.h +++ /dev/null @@ -1,288 +0,0 @@ -#pragma once -// MESSAGE CAMERA_SETTINGS PACKING - -#define MAVLINK_MSG_ID_CAMERA_SETTINGS 260 - -MAVPACKED( -typedef struct __mavlink_camera_settings_t { - uint32_t time_boot_ms; /*< [ms] Timestamp (time since system boot).*/ - uint8_t mode_id; /*< Camera mode*/ - float zoomLevel; /*< Current zoom level as a percentage of the full range (0.0 to 100.0, NaN if not known)*/ - float focusLevel; /*< Current focus level as a percentage of the full range (0.0 to 100.0, NaN if not known)*/ -}) mavlink_camera_settings_t; - -#define MAVLINK_MSG_ID_CAMERA_SETTINGS_LEN 13 -#define MAVLINK_MSG_ID_CAMERA_SETTINGS_MIN_LEN 5 -#define MAVLINK_MSG_ID_260_LEN 13 -#define MAVLINK_MSG_ID_260_MIN_LEN 5 - -#define MAVLINK_MSG_ID_CAMERA_SETTINGS_CRC 146 -#define MAVLINK_MSG_ID_260_CRC 146 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_CAMERA_SETTINGS { \ - 260, \ - "CAMERA_SETTINGS", \ - 4, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_camera_settings_t, time_boot_ms) }, \ - { "mode_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_camera_settings_t, mode_id) }, \ - { "zoomLevel", NULL, MAVLINK_TYPE_FLOAT, 0, 5, offsetof(mavlink_camera_settings_t, zoomLevel) }, \ - { "focusLevel", NULL, MAVLINK_TYPE_FLOAT, 0, 9, offsetof(mavlink_camera_settings_t, focusLevel) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_CAMERA_SETTINGS { \ - "CAMERA_SETTINGS", \ - 4, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_camera_settings_t, time_boot_ms) }, \ - { "mode_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_camera_settings_t, mode_id) }, \ - { "zoomLevel", NULL, MAVLINK_TYPE_FLOAT, 0, 5, offsetof(mavlink_camera_settings_t, zoomLevel) }, \ - { "focusLevel", NULL, MAVLINK_TYPE_FLOAT, 0, 9, offsetof(mavlink_camera_settings_t, focusLevel) }, \ - } \ -} -#endif - -/** - * @brief Pack a camera_settings message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param time_boot_ms [ms] Timestamp (time since system boot). - * @param mode_id Camera mode - * @param zoomLevel Current zoom level as a percentage of the full range (0.0 to 100.0, NaN if not known) - * @param focusLevel Current focus level as a percentage of the full range (0.0 to 100.0, NaN if not known) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_camera_settings_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint32_t time_boot_ms, uint8_t mode_id, float zoomLevel, float focusLevel) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_CAMERA_SETTINGS_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_uint8_t(buf, 4, mode_id); - _mav_put_float(buf, 5, zoomLevel); - _mav_put_float(buf, 9, focusLevel); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CAMERA_SETTINGS_LEN); -#else - mavlink_camera_settings_t packet; - packet.time_boot_ms = time_boot_ms; - packet.mode_id = mode_id; - packet.zoomLevel = zoomLevel; - packet.focusLevel = focusLevel; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CAMERA_SETTINGS_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_CAMERA_SETTINGS; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_CAMERA_SETTINGS_MIN_LEN, MAVLINK_MSG_ID_CAMERA_SETTINGS_LEN, MAVLINK_MSG_ID_CAMERA_SETTINGS_CRC); -} - -/** - * @brief Pack a camera_settings message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_boot_ms [ms] Timestamp (time since system boot). - * @param mode_id Camera mode - * @param zoomLevel Current zoom level as a percentage of the full range (0.0 to 100.0, NaN if not known) - * @param focusLevel Current focus level as a percentage of the full range (0.0 to 100.0, NaN if not known) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_camera_settings_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint32_t time_boot_ms,uint8_t mode_id,float zoomLevel,float focusLevel) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_CAMERA_SETTINGS_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_uint8_t(buf, 4, mode_id); - _mav_put_float(buf, 5, zoomLevel); - _mav_put_float(buf, 9, focusLevel); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CAMERA_SETTINGS_LEN); -#else - mavlink_camera_settings_t packet; - packet.time_boot_ms = time_boot_ms; - packet.mode_id = mode_id; - packet.zoomLevel = zoomLevel; - packet.focusLevel = focusLevel; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CAMERA_SETTINGS_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_CAMERA_SETTINGS; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_CAMERA_SETTINGS_MIN_LEN, MAVLINK_MSG_ID_CAMERA_SETTINGS_LEN, MAVLINK_MSG_ID_CAMERA_SETTINGS_CRC); -} - -/** - * @brief Encode a camera_settings struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param camera_settings C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_camera_settings_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_camera_settings_t* camera_settings) -{ - return mavlink_msg_camera_settings_pack(system_id, component_id, msg, camera_settings->time_boot_ms, camera_settings->mode_id, camera_settings->zoomLevel, camera_settings->focusLevel); -} - -/** - * @brief Encode a camera_settings struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param camera_settings C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_camera_settings_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_camera_settings_t* camera_settings) -{ - return mavlink_msg_camera_settings_pack_chan(system_id, component_id, chan, msg, camera_settings->time_boot_ms, camera_settings->mode_id, camera_settings->zoomLevel, camera_settings->focusLevel); -} - -/** - * @brief Send a camera_settings message - * @param chan MAVLink channel to send the message - * - * @param time_boot_ms [ms] Timestamp (time since system boot). - * @param mode_id Camera mode - * @param zoomLevel Current zoom level as a percentage of the full range (0.0 to 100.0, NaN if not known) - * @param focusLevel Current focus level as a percentage of the full range (0.0 to 100.0, NaN if not known) - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_camera_settings_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t mode_id, float zoomLevel, float focusLevel) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_CAMERA_SETTINGS_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_uint8_t(buf, 4, mode_id); - _mav_put_float(buf, 5, zoomLevel); - _mav_put_float(buf, 9, focusLevel); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_SETTINGS, buf, MAVLINK_MSG_ID_CAMERA_SETTINGS_MIN_LEN, MAVLINK_MSG_ID_CAMERA_SETTINGS_LEN, MAVLINK_MSG_ID_CAMERA_SETTINGS_CRC); -#else - mavlink_camera_settings_t packet; - packet.time_boot_ms = time_boot_ms; - packet.mode_id = mode_id; - packet.zoomLevel = zoomLevel; - packet.focusLevel = focusLevel; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_SETTINGS, (const char *)&packet, MAVLINK_MSG_ID_CAMERA_SETTINGS_MIN_LEN, MAVLINK_MSG_ID_CAMERA_SETTINGS_LEN, MAVLINK_MSG_ID_CAMERA_SETTINGS_CRC); -#endif -} - -/** - * @brief Send a camera_settings message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_camera_settings_send_struct(mavlink_channel_t chan, const mavlink_camera_settings_t* camera_settings) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_camera_settings_send(chan, camera_settings->time_boot_ms, camera_settings->mode_id, camera_settings->zoomLevel, camera_settings->focusLevel); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_SETTINGS, (const char *)camera_settings, MAVLINK_MSG_ID_CAMERA_SETTINGS_MIN_LEN, MAVLINK_MSG_ID_CAMERA_SETTINGS_LEN, MAVLINK_MSG_ID_CAMERA_SETTINGS_CRC); -#endif -} - -#if MAVLINK_MSG_ID_CAMERA_SETTINGS_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_camera_settings_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t mode_id, float zoomLevel, float focusLevel) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_uint8_t(buf, 4, mode_id); - _mav_put_float(buf, 5, zoomLevel); - _mav_put_float(buf, 9, focusLevel); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_SETTINGS, buf, MAVLINK_MSG_ID_CAMERA_SETTINGS_MIN_LEN, MAVLINK_MSG_ID_CAMERA_SETTINGS_LEN, MAVLINK_MSG_ID_CAMERA_SETTINGS_CRC); -#else - mavlink_camera_settings_t *packet = (mavlink_camera_settings_t *)msgbuf; - packet->time_boot_ms = time_boot_ms; - packet->mode_id = mode_id; - packet->zoomLevel = zoomLevel; - packet->focusLevel = focusLevel; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_SETTINGS, (const char *)packet, MAVLINK_MSG_ID_CAMERA_SETTINGS_MIN_LEN, MAVLINK_MSG_ID_CAMERA_SETTINGS_LEN, MAVLINK_MSG_ID_CAMERA_SETTINGS_CRC); -#endif -} -#endif - -#endif - -// MESSAGE CAMERA_SETTINGS UNPACKING - - -/** - * @brief Get field time_boot_ms from camera_settings message - * - * @return [ms] Timestamp (time since system boot). - */ -static inline uint32_t mavlink_msg_camera_settings_get_time_boot_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field mode_id from camera_settings message - * - * @return Camera mode - */ -static inline uint8_t mavlink_msg_camera_settings_get_mode_id(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 4); -} - -/** - * @brief Get field zoomLevel from camera_settings message - * - * @return Current zoom level as a percentage of the full range (0.0 to 100.0, NaN if not known) - */ -static inline float mavlink_msg_camera_settings_get_zoomLevel(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 5); -} - -/** - * @brief Get field focusLevel from camera_settings message - * - * @return Current focus level as a percentage of the full range (0.0 to 100.0, NaN if not known) - */ -static inline float mavlink_msg_camera_settings_get_focusLevel(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 9); -} - -/** - * @brief Decode a camera_settings message into a struct - * - * @param msg The message to decode - * @param camera_settings C-struct to decode the message contents into - */ -static inline void mavlink_msg_camera_settings_decode(const mavlink_message_t* msg, mavlink_camera_settings_t* camera_settings) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - camera_settings->time_boot_ms = mavlink_msg_camera_settings_get_time_boot_ms(msg); - camera_settings->mode_id = mavlink_msg_camera_settings_get_mode_id(msg); - camera_settings->zoomLevel = mavlink_msg_camera_settings_get_zoomLevel(msg); - camera_settings->focusLevel = mavlink_msg_camera_settings_get_focusLevel(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_CAMERA_SETTINGS_LEN? msg->len : MAVLINK_MSG_ID_CAMERA_SETTINGS_LEN; - memset(camera_settings, 0, MAVLINK_MSG_ID_CAMERA_SETTINGS_LEN); - memcpy(camera_settings, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_camera_tracking_geo_status.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_camera_tracking_geo_status.h deleted file mode 100644 index 120b1e3d..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_camera_tracking_geo_status.h +++ /dev/null @@ -1,513 +0,0 @@ -#pragma once -// MESSAGE CAMERA_TRACKING_GEO_STATUS PACKING - -#define MAVLINK_MSG_ID_CAMERA_TRACKING_GEO_STATUS 276 - - -typedef struct __mavlink_camera_tracking_geo_status_t { - int32_t lat; /*< [degE7] Latitude of tracked object*/ - int32_t lon; /*< [degE7] Longitude of tracked object*/ - float alt; /*< [m] Altitude of tracked object(AMSL, WGS84)*/ - float h_acc; /*< [m] Horizontal accuracy. NAN if unknown*/ - float v_acc; /*< [m] Vertical accuracy. NAN if unknown*/ - float vel_n; /*< [m/s] North velocity of tracked object. NAN if unknown*/ - float vel_e; /*< [m/s] East velocity of tracked object. NAN if unknown*/ - float vel_d; /*< [m/s] Down velocity of tracked object. NAN if unknown*/ - float vel_acc; /*< [m/s] Velocity accuracy. NAN if unknown*/ - float dist; /*< [m] Distance between camera and tracked object. NAN if unknown*/ - float hdg; /*< [rad] Heading in radians, in NED. NAN if unknown*/ - float hdg_acc; /*< [rad] Accuracy of heading, in NED. NAN if unknown*/ - uint8_t tracking_status; /*< Current tracking status*/ -} mavlink_camera_tracking_geo_status_t; - -#define MAVLINK_MSG_ID_CAMERA_TRACKING_GEO_STATUS_LEN 49 -#define MAVLINK_MSG_ID_CAMERA_TRACKING_GEO_STATUS_MIN_LEN 49 -#define MAVLINK_MSG_ID_276_LEN 49 -#define MAVLINK_MSG_ID_276_MIN_LEN 49 - -#define MAVLINK_MSG_ID_CAMERA_TRACKING_GEO_STATUS_CRC 18 -#define MAVLINK_MSG_ID_276_CRC 18 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_CAMERA_TRACKING_GEO_STATUS { \ - 276, \ - "CAMERA_TRACKING_GEO_STATUS", \ - 13, \ - { { "tracking_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 48, offsetof(mavlink_camera_tracking_geo_status_t, tracking_status) }, \ - { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_camera_tracking_geo_status_t, lat) }, \ - { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_camera_tracking_geo_status_t, lon) }, \ - { "alt", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_camera_tracking_geo_status_t, alt) }, \ - { "h_acc", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_camera_tracking_geo_status_t, h_acc) }, \ - { "v_acc", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_camera_tracking_geo_status_t, v_acc) }, \ - { "vel_n", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_camera_tracking_geo_status_t, vel_n) }, \ - { "vel_e", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_camera_tracking_geo_status_t, vel_e) }, \ - { "vel_d", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_camera_tracking_geo_status_t, vel_d) }, \ - { "vel_acc", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_camera_tracking_geo_status_t, vel_acc) }, \ - { "dist", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_camera_tracking_geo_status_t, dist) }, \ - { "hdg", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_camera_tracking_geo_status_t, hdg) }, \ - { "hdg_acc", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_camera_tracking_geo_status_t, hdg_acc) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_CAMERA_TRACKING_GEO_STATUS { \ - "CAMERA_TRACKING_GEO_STATUS", \ - 13, \ - { { "tracking_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 48, offsetof(mavlink_camera_tracking_geo_status_t, tracking_status) }, \ - { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_camera_tracking_geo_status_t, lat) }, \ - { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_camera_tracking_geo_status_t, lon) }, \ - { "alt", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_camera_tracking_geo_status_t, alt) }, \ - { "h_acc", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_camera_tracking_geo_status_t, h_acc) }, \ - { "v_acc", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_camera_tracking_geo_status_t, v_acc) }, \ - { "vel_n", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_camera_tracking_geo_status_t, vel_n) }, \ - { "vel_e", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_camera_tracking_geo_status_t, vel_e) }, \ - { "vel_d", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_camera_tracking_geo_status_t, vel_d) }, \ - { "vel_acc", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_camera_tracking_geo_status_t, vel_acc) }, \ - { "dist", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_camera_tracking_geo_status_t, dist) }, \ - { "hdg", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_camera_tracking_geo_status_t, hdg) }, \ - { "hdg_acc", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_camera_tracking_geo_status_t, hdg_acc) }, \ - } \ -} -#endif - -/** - * @brief Pack a camera_tracking_geo_status message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param tracking_status Current tracking status - * @param lat [degE7] Latitude of tracked object - * @param lon [degE7] Longitude of tracked object - * @param alt [m] Altitude of tracked object(AMSL, WGS84) - * @param h_acc [m] Horizontal accuracy. NAN if unknown - * @param v_acc [m] Vertical accuracy. NAN if unknown - * @param vel_n [m/s] North velocity of tracked object. NAN if unknown - * @param vel_e [m/s] East velocity of tracked object. NAN if unknown - * @param vel_d [m/s] Down velocity of tracked object. NAN if unknown - * @param vel_acc [m/s] Velocity accuracy. NAN if unknown - * @param dist [m] Distance between camera and tracked object. NAN if unknown - * @param hdg [rad] Heading in radians, in NED. NAN if unknown - * @param hdg_acc [rad] Accuracy of heading, in NED. NAN if unknown - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_camera_tracking_geo_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t tracking_status, int32_t lat, int32_t lon, float alt, float h_acc, float v_acc, float vel_n, float vel_e, float vel_d, float vel_acc, float dist, float hdg, float hdg_acc) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_CAMERA_TRACKING_GEO_STATUS_LEN]; - _mav_put_int32_t(buf, 0, lat); - _mav_put_int32_t(buf, 4, lon); - _mav_put_float(buf, 8, alt); - _mav_put_float(buf, 12, h_acc); - _mav_put_float(buf, 16, v_acc); - _mav_put_float(buf, 20, vel_n); - _mav_put_float(buf, 24, vel_e); - _mav_put_float(buf, 28, vel_d); - _mav_put_float(buf, 32, vel_acc); - _mav_put_float(buf, 36, dist); - _mav_put_float(buf, 40, hdg); - _mav_put_float(buf, 44, hdg_acc); - _mav_put_uint8_t(buf, 48, tracking_status); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CAMERA_TRACKING_GEO_STATUS_LEN); -#else - mavlink_camera_tracking_geo_status_t packet; - packet.lat = lat; - packet.lon = lon; - packet.alt = alt; - packet.h_acc = h_acc; - packet.v_acc = v_acc; - packet.vel_n = vel_n; - packet.vel_e = vel_e; - packet.vel_d = vel_d; - packet.vel_acc = vel_acc; - packet.dist = dist; - packet.hdg = hdg; - packet.hdg_acc = hdg_acc; - packet.tracking_status = tracking_status; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CAMERA_TRACKING_GEO_STATUS_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_CAMERA_TRACKING_GEO_STATUS; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_CAMERA_TRACKING_GEO_STATUS_MIN_LEN, MAVLINK_MSG_ID_CAMERA_TRACKING_GEO_STATUS_LEN, MAVLINK_MSG_ID_CAMERA_TRACKING_GEO_STATUS_CRC); -} - -/** - * @brief Pack a camera_tracking_geo_status message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param tracking_status Current tracking status - * @param lat [degE7] Latitude of tracked object - * @param lon [degE7] Longitude of tracked object - * @param alt [m] Altitude of tracked object(AMSL, WGS84) - * @param h_acc [m] Horizontal accuracy. NAN if unknown - * @param v_acc [m] Vertical accuracy. NAN if unknown - * @param vel_n [m/s] North velocity of tracked object. NAN if unknown - * @param vel_e [m/s] East velocity of tracked object. NAN if unknown - * @param vel_d [m/s] Down velocity of tracked object. NAN if unknown - * @param vel_acc [m/s] Velocity accuracy. NAN if unknown - * @param dist [m] Distance between camera and tracked object. NAN if unknown - * @param hdg [rad] Heading in radians, in NED. NAN if unknown - * @param hdg_acc [rad] Accuracy of heading, in NED. NAN if unknown - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_camera_tracking_geo_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t tracking_status,int32_t lat,int32_t lon,float alt,float h_acc,float v_acc,float vel_n,float vel_e,float vel_d,float vel_acc,float dist,float hdg,float hdg_acc) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_CAMERA_TRACKING_GEO_STATUS_LEN]; - _mav_put_int32_t(buf, 0, lat); - _mav_put_int32_t(buf, 4, lon); - _mav_put_float(buf, 8, alt); - _mav_put_float(buf, 12, h_acc); - _mav_put_float(buf, 16, v_acc); - _mav_put_float(buf, 20, vel_n); - _mav_put_float(buf, 24, vel_e); - _mav_put_float(buf, 28, vel_d); - _mav_put_float(buf, 32, vel_acc); - _mav_put_float(buf, 36, dist); - _mav_put_float(buf, 40, hdg); - _mav_put_float(buf, 44, hdg_acc); - _mav_put_uint8_t(buf, 48, tracking_status); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CAMERA_TRACKING_GEO_STATUS_LEN); -#else - mavlink_camera_tracking_geo_status_t packet; - packet.lat = lat; - packet.lon = lon; - packet.alt = alt; - packet.h_acc = h_acc; - packet.v_acc = v_acc; - packet.vel_n = vel_n; - packet.vel_e = vel_e; - packet.vel_d = vel_d; - packet.vel_acc = vel_acc; - packet.dist = dist; - packet.hdg = hdg; - packet.hdg_acc = hdg_acc; - packet.tracking_status = tracking_status; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CAMERA_TRACKING_GEO_STATUS_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_CAMERA_TRACKING_GEO_STATUS; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_CAMERA_TRACKING_GEO_STATUS_MIN_LEN, MAVLINK_MSG_ID_CAMERA_TRACKING_GEO_STATUS_LEN, MAVLINK_MSG_ID_CAMERA_TRACKING_GEO_STATUS_CRC); -} - -/** - * @brief Encode a camera_tracking_geo_status struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param camera_tracking_geo_status C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_camera_tracking_geo_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_camera_tracking_geo_status_t* camera_tracking_geo_status) -{ - return mavlink_msg_camera_tracking_geo_status_pack(system_id, component_id, msg, camera_tracking_geo_status->tracking_status, camera_tracking_geo_status->lat, camera_tracking_geo_status->lon, camera_tracking_geo_status->alt, camera_tracking_geo_status->h_acc, camera_tracking_geo_status->v_acc, camera_tracking_geo_status->vel_n, camera_tracking_geo_status->vel_e, camera_tracking_geo_status->vel_d, camera_tracking_geo_status->vel_acc, camera_tracking_geo_status->dist, camera_tracking_geo_status->hdg, camera_tracking_geo_status->hdg_acc); -} - -/** - * @brief Encode a camera_tracking_geo_status struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param camera_tracking_geo_status C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_camera_tracking_geo_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_camera_tracking_geo_status_t* camera_tracking_geo_status) -{ - return mavlink_msg_camera_tracking_geo_status_pack_chan(system_id, component_id, chan, msg, camera_tracking_geo_status->tracking_status, camera_tracking_geo_status->lat, camera_tracking_geo_status->lon, camera_tracking_geo_status->alt, camera_tracking_geo_status->h_acc, camera_tracking_geo_status->v_acc, camera_tracking_geo_status->vel_n, camera_tracking_geo_status->vel_e, camera_tracking_geo_status->vel_d, camera_tracking_geo_status->vel_acc, camera_tracking_geo_status->dist, camera_tracking_geo_status->hdg, camera_tracking_geo_status->hdg_acc); -} - -/** - * @brief Send a camera_tracking_geo_status message - * @param chan MAVLink channel to send the message - * - * @param tracking_status Current tracking status - * @param lat [degE7] Latitude of tracked object - * @param lon [degE7] Longitude of tracked object - * @param alt [m] Altitude of tracked object(AMSL, WGS84) - * @param h_acc [m] Horizontal accuracy. NAN if unknown - * @param v_acc [m] Vertical accuracy. NAN if unknown - * @param vel_n [m/s] North velocity of tracked object. NAN if unknown - * @param vel_e [m/s] East velocity of tracked object. NAN if unknown - * @param vel_d [m/s] Down velocity of tracked object. NAN if unknown - * @param vel_acc [m/s] Velocity accuracy. NAN if unknown - * @param dist [m] Distance between camera and tracked object. NAN if unknown - * @param hdg [rad] Heading in radians, in NED. NAN if unknown - * @param hdg_acc [rad] Accuracy of heading, in NED. NAN if unknown - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_camera_tracking_geo_status_send(mavlink_channel_t chan, uint8_t tracking_status, int32_t lat, int32_t lon, float alt, float h_acc, float v_acc, float vel_n, float vel_e, float vel_d, float vel_acc, float dist, float hdg, float hdg_acc) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_CAMERA_TRACKING_GEO_STATUS_LEN]; - _mav_put_int32_t(buf, 0, lat); - _mav_put_int32_t(buf, 4, lon); - _mav_put_float(buf, 8, alt); - _mav_put_float(buf, 12, h_acc); - _mav_put_float(buf, 16, v_acc); - _mav_put_float(buf, 20, vel_n); - _mav_put_float(buf, 24, vel_e); - _mav_put_float(buf, 28, vel_d); - _mav_put_float(buf, 32, vel_acc); - _mav_put_float(buf, 36, dist); - _mav_put_float(buf, 40, hdg); - _mav_put_float(buf, 44, hdg_acc); - _mav_put_uint8_t(buf, 48, tracking_status); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_TRACKING_GEO_STATUS, buf, MAVLINK_MSG_ID_CAMERA_TRACKING_GEO_STATUS_MIN_LEN, MAVLINK_MSG_ID_CAMERA_TRACKING_GEO_STATUS_LEN, MAVLINK_MSG_ID_CAMERA_TRACKING_GEO_STATUS_CRC); -#else - mavlink_camera_tracking_geo_status_t packet; - packet.lat = lat; - packet.lon = lon; - packet.alt = alt; - packet.h_acc = h_acc; - packet.v_acc = v_acc; - packet.vel_n = vel_n; - packet.vel_e = vel_e; - packet.vel_d = vel_d; - packet.vel_acc = vel_acc; - packet.dist = dist; - packet.hdg = hdg; - packet.hdg_acc = hdg_acc; - packet.tracking_status = tracking_status; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_TRACKING_GEO_STATUS, (const char *)&packet, MAVLINK_MSG_ID_CAMERA_TRACKING_GEO_STATUS_MIN_LEN, MAVLINK_MSG_ID_CAMERA_TRACKING_GEO_STATUS_LEN, MAVLINK_MSG_ID_CAMERA_TRACKING_GEO_STATUS_CRC); -#endif -} - -/** - * @brief Send a camera_tracking_geo_status message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_camera_tracking_geo_status_send_struct(mavlink_channel_t chan, const mavlink_camera_tracking_geo_status_t* camera_tracking_geo_status) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_camera_tracking_geo_status_send(chan, camera_tracking_geo_status->tracking_status, camera_tracking_geo_status->lat, camera_tracking_geo_status->lon, camera_tracking_geo_status->alt, camera_tracking_geo_status->h_acc, camera_tracking_geo_status->v_acc, camera_tracking_geo_status->vel_n, camera_tracking_geo_status->vel_e, camera_tracking_geo_status->vel_d, camera_tracking_geo_status->vel_acc, camera_tracking_geo_status->dist, camera_tracking_geo_status->hdg, camera_tracking_geo_status->hdg_acc); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_TRACKING_GEO_STATUS, (const char *)camera_tracking_geo_status, MAVLINK_MSG_ID_CAMERA_TRACKING_GEO_STATUS_MIN_LEN, MAVLINK_MSG_ID_CAMERA_TRACKING_GEO_STATUS_LEN, MAVLINK_MSG_ID_CAMERA_TRACKING_GEO_STATUS_CRC); -#endif -} - -#if MAVLINK_MSG_ID_CAMERA_TRACKING_GEO_STATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_camera_tracking_geo_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t tracking_status, int32_t lat, int32_t lon, float alt, float h_acc, float v_acc, float vel_n, float vel_e, float vel_d, float vel_acc, float dist, float hdg, float hdg_acc) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_int32_t(buf, 0, lat); - _mav_put_int32_t(buf, 4, lon); - _mav_put_float(buf, 8, alt); - _mav_put_float(buf, 12, h_acc); - _mav_put_float(buf, 16, v_acc); - _mav_put_float(buf, 20, vel_n); - _mav_put_float(buf, 24, vel_e); - _mav_put_float(buf, 28, vel_d); - _mav_put_float(buf, 32, vel_acc); - _mav_put_float(buf, 36, dist); - _mav_put_float(buf, 40, hdg); - _mav_put_float(buf, 44, hdg_acc); - _mav_put_uint8_t(buf, 48, tracking_status); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_TRACKING_GEO_STATUS, buf, MAVLINK_MSG_ID_CAMERA_TRACKING_GEO_STATUS_MIN_LEN, MAVLINK_MSG_ID_CAMERA_TRACKING_GEO_STATUS_LEN, MAVLINK_MSG_ID_CAMERA_TRACKING_GEO_STATUS_CRC); -#else - mavlink_camera_tracking_geo_status_t *packet = (mavlink_camera_tracking_geo_status_t *)msgbuf; - packet->lat = lat; - packet->lon = lon; - packet->alt = alt; - packet->h_acc = h_acc; - packet->v_acc = v_acc; - packet->vel_n = vel_n; - packet->vel_e = vel_e; - packet->vel_d = vel_d; - packet->vel_acc = vel_acc; - packet->dist = dist; - packet->hdg = hdg; - packet->hdg_acc = hdg_acc; - packet->tracking_status = tracking_status; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_TRACKING_GEO_STATUS, (const char *)packet, MAVLINK_MSG_ID_CAMERA_TRACKING_GEO_STATUS_MIN_LEN, MAVLINK_MSG_ID_CAMERA_TRACKING_GEO_STATUS_LEN, MAVLINK_MSG_ID_CAMERA_TRACKING_GEO_STATUS_CRC); -#endif -} -#endif - -#endif - -// MESSAGE CAMERA_TRACKING_GEO_STATUS UNPACKING - - -/** - * @brief Get field tracking_status from camera_tracking_geo_status message - * - * @return Current tracking status - */ -static inline uint8_t mavlink_msg_camera_tracking_geo_status_get_tracking_status(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 48); -} - -/** - * @brief Get field lat from camera_tracking_geo_status message - * - * @return [degE7] Latitude of tracked object - */ -static inline int32_t mavlink_msg_camera_tracking_geo_status_get_lat(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 0); -} - -/** - * @brief Get field lon from camera_tracking_geo_status message - * - * @return [degE7] Longitude of tracked object - */ -static inline int32_t mavlink_msg_camera_tracking_geo_status_get_lon(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 4); -} - -/** - * @brief Get field alt from camera_tracking_geo_status message - * - * @return [m] Altitude of tracked object(AMSL, WGS84) - */ -static inline float mavlink_msg_camera_tracking_geo_status_get_alt(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field h_acc from camera_tracking_geo_status message - * - * @return [m] Horizontal accuracy. NAN if unknown - */ -static inline float mavlink_msg_camera_tracking_geo_status_get_h_acc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field v_acc from camera_tracking_geo_status message - * - * @return [m] Vertical accuracy. NAN if unknown - */ -static inline float mavlink_msg_camera_tracking_geo_status_get_v_acc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field vel_n from camera_tracking_geo_status message - * - * @return [m/s] North velocity of tracked object. NAN if unknown - */ -static inline float mavlink_msg_camera_tracking_geo_status_get_vel_n(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Get field vel_e from camera_tracking_geo_status message - * - * @return [m/s] East velocity of tracked object. NAN if unknown - */ -static inline float mavlink_msg_camera_tracking_geo_status_get_vel_e(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Get field vel_d from camera_tracking_geo_status message - * - * @return [m/s] Down velocity of tracked object. NAN if unknown - */ -static inline float mavlink_msg_camera_tracking_geo_status_get_vel_d(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 28); -} - -/** - * @brief Get field vel_acc from camera_tracking_geo_status message - * - * @return [m/s] Velocity accuracy. NAN if unknown - */ -static inline float mavlink_msg_camera_tracking_geo_status_get_vel_acc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 32); -} - -/** - * @brief Get field dist from camera_tracking_geo_status message - * - * @return [m] Distance between camera and tracked object. NAN if unknown - */ -static inline float mavlink_msg_camera_tracking_geo_status_get_dist(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 36); -} - -/** - * @brief Get field hdg from camera_tracking_geo_status message - * - * @return [rad] Heading in radians, in NED. NAN if unknown - */ -static inline float mavlink_msg_camera_tracking_geo_status_get_hdg(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 40); -} - -/** - * @brief Get field hdg_acc from camera_tracking_geo_status message - * - * @return [rad] Accuracy of heading, in NED. NAN if unknown - */ -static inline float mavlink_msg_camera_tracking_geo_status_get_hdg_acc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 44); -} - -/** - * @brief Decode a camera_tracking_geo_status message into a struct - * - * @param msg The message to decode - * @param camera_tracking_geo_status C-struct to decode the message contents into - */ -static inline void mavlink_msg_camera_tracking_geo_status_decode(const mavlink_message_t* msg, mavlink_camera_tracking_geo_status_t* camera_tracking_geo_status) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - camera_tracking_geo_status->lat = mavlink_msg_camera_tracking_geo_status_get_lat(msg); - camera_tracking_geo_status->lon = mavlink_msg_camera_tracking_geo_status_get_lon(msg); - camera_tracking_geo_status->alt = mavlink_msg_camera_tracking_geo_status_get_alt(msg); - camera_tracking_geo_status->h_acc = mavlink_msg_camera_tracking_geo_status_get_h_acc(msg); - camera_tracking_geo_status->v_acc = mavlink_msg_camera_tracking_geo_status_get_v_acc(msg); - camera_tracking_geo_status->vel_n = mavlink_msg_camera_tracking_geo_status_get_vel_n(msg); - camera_tracking_geo_status->vel_e = mavlink_msg_camera_tracking_geo_status_get_vel_e(msg); - camera_tracking_geo_status->vel_d = mavlink_msg_camera_tracking_geo_status_get_vel_d(msg); - camera_tracking_geo_status->vel_acc = mavlink_msg_camera_tracking_geo_status_get_vel_acc(msg); - camera_tracking_geo_status->dist = mavlink_msg_camera_tracking_geo_status_get_dist(msg); - camera_tracking_geo_status->hdg = mavlink_msg_camera_tracking_geo_status_get_hdg(msg); - camera_tracking_geo_status->hdg_acc = mavlink_msg_camera_tracking_geo_status_get_hdg_acc(msg); - camera_tracking_geo_status->tracking_status = mavlink_msg_camera_tracking_geo_status_get_tracking_status(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_CAMERA_TRACKING_GEO_STATUS_LEN? msg->len : MAVLINK_MSG_ID_CAMERA_TRACKING_GEO_STATUS_LEN; - memset(camera_tracking_geo_status, 0, MAVLINK_MSG_ID_CAMERA_TRACKING_GEO_STATUS_LEN); - memcpy(camera_tracking_geo_status, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_camera_tracking_image_status.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_camera_tracking_image_status.h deleted file mode 100644 index bd5f0607..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_camera_tracking_image_status.h +++ /dev/null @@ -1,438 +0,0 @@ -#pragma once -// MESSAGE CAMERA_TRACKING_IMAGE_STATUS PACKING - -#define MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS 275 - - -typedef struct __mavlink_camera_tracking_image_status_t { - float point_x; /*< Current tracked point x value if CAMERA_TRACKING_MODE_POINT (normalized 0..1, 0 is left, 1 is right), NAN if unknown*/ - float point_y; /*< Current tracked point y value if CAMERA_TRACKING_MODE_POINT (normalized 0..1, 0 is top, 1 is bottom), NAN if unknown*/ - float radius; /*< Current tracked radius if CAMERA_TRACKING_MODE_POINT (normalized 0..1, 0 is image left, 1 is image right), NAN if unknown*/ - float rec_top_x; /*< Current tracked rectangle top x value if CAMERA_TRACKING_MODE_RECTANGLE (normalized 0..1, 0 is left, 1 is right), NAN if unknown*/ - float rec_top_y; /*< Current tracked rectangle top y value if CAMERA_TRACKING_MODE_RECTANGLE (normalized 0..1, 0 is top, 1 is bottom), NAN if unknown*/ - float rec_bottom_x; /*< Current tracked rectangle bottom x value if CAMERA_TRACKING_MODE_RECTANGLE (normalized 0..1, 0 is left, 1 is right), NAN if unknown*/ - float rec_bottom_y; /*< Current tracked rectangle bottom y value if CAMERA_TRACKING_MODE_RECTANGLE (normalized 0..1, 0 is top, 1 is bottom), NAN if unknown*/ - uint8_t tracking_status; /*< Current tracking status*/ - uint8_t tracking_mode; /*< Current tracking mode*/ - uint8_t target_data; /*< Defines location of target data*/ -} mavlink_camera_tracking_image_status_t; - -#define MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS_LEN 31 -#define MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS_MIN_LEN 31 -#define MAVLINK_MSG_ID_275_LEN 31 -#define MAVLINK_MSG_ID_275_MIN_LEN 31 - -#define MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS_CRC 126 -#define MAVLINK_MSG_ID_275_CRC 126 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_CAMERA_TRACKING_IMAGE_STATUS { \ - 275, \ - "CAMERA_TRACKING_IMAGE_STATUS", \ - 10, \ - { { "tracking_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 28, offsetof(mavlink_camera_tracking_image_status_t, tracking_status) }, \ - { "tracking_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 29, offsetof(mavlink_camera_tracking_image_status_t, tracking_mode) }, \ - { "target_data", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_camera_tracking_image_status_t, target_data) }, \ - { "point_x", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_camera_tracking_image_status_t, point_x) }, \ - { "point_y", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_camera_tracking_image_status_t, point_y) }, \ - { "radius", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_camera_tracking_image_status_t, radius) }, \ - { "rec_top_x", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_camera_tracking_image_status_t, rec_top_x) }, \ - { "rec_top_y", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_camera_tracking_image_status_t, rec_top_y) }, \ - { "rec_bottom_x", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_camera_tracking_image_status_t, rec_bottom_x) }, \ - { "rec_bottom_y", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_camera_tracking_image_status_t, rec_bottom_y) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_CAMERA_TRACKING_IMAGE_STATUS { \ - "CAMERA_TRACKING_IMAGE_STATUS", \ - 10, \ - { { "tracking_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 28, offsetof(mavlink_camera_tracking_image_status_t, tracking_status) }, \ - { "tracking_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 29, offsetof(mavlink_camera_tracking_image_status_t, tracking_mode) }, \ - { "target_data", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_camera_tracking_image_status_t, target_data) }, \ - { "point_x", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_camera_tracking_image_status_t, point_x) }, \ - { "point_y", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_camera_tracking_image_status_t, point_y) }, \ - { "radius", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_camera_tracking_image_status_t, radius) }, \ - { "rec_top_x", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_camera_tracking_image_status_t, rec_top_x) }, \ - { "rec_top_y", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_camera_tracking_image_status_t, rec_top_y) }, \ - { "rec_bottom_x", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_camera_tracking_image_status_t, rec_bottom_x) }, \ - { "rec_bottom_y", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_camera_tracking_image_status_t, rec_bottom_y) }, \ - } \ -} -#endif - -/** - * @brief Pack a camera_tracking_image_status message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param tracking_status Current tracking status - * @param tracking_mode Current tracking mode - * @param target_data Defines location of target data - * @param point_x Current tracked point x value if CAMERA_TRACKING_MODE_POINT (normalized 0..1, 0 is left, 1 is right), NAN if unknown - * @param point_y Current tracked point y value if CAMERA_TRACKING_MODE_POINT (normalized 0..1, 0 is top, 1 is bottom), NAN if unknown - * @param radius Current tracked radius if CAMERA_TRACKING_MODE_POINT (normalized 0..1, 0 is image left, 1 is image right), NAN if unknown - * @param rec_top_x Current tracked rectangle top x value if CAMERA_TRACKING_MODE_RECTANGLE (normalized 0..1, 0 is left, 1 is right), NAN if unknown - * @param rec_top_y Current tracked rectangle top y value if CAMERA_TRACKING_MODE_RECTANGLE (normalized 0..1, 0 is top, 1 is bottom), NAN if unknown - * @param rec_bottom_x Current tracked rectangle bottom x value if CAMERA_TRACKING_MODE_RECTANGLE (normalized 0..1, 0 is left, 1 is right), NAN if unknown - * @param rec_bottom_y Current tracked rectangle bottom y value if CAMERA_TRACKING_MODE_RECTANGLE (normalized 0..1, 0 is top, 1 is bottom), NAN if unknown - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_camera_tracking_image_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t tracking_status, uint8_t tracking_mode, uint8_t target_data, float point_x, float point_y, float radius, float rec_top_x, float rec_top_y, float rec_bottom_x, float rec_bottom_y) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS_LEN]; - _mav_put_float(buf, 0, point_x); - _mav_put_float(buf, 4, point_y); - _mav_put_float(buf, 8, radius); - _mav_put_float(buf, 12, rec_top_x); - _mav_put_float(buf, 16, rec_top_y); - _mav_put_float(buf, 20, rec_bottom_x); - _mav_put_float(buf, 24, rec_bottom_y); - _mav_put_uint8_t(buf, 28, tracking_status); - _mav_put_uint8_t(buf, 29, tracking_mode); - _mav_put_uint8_t(buf, 30, target_data); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS_LEN); -#else - mavlink_camera_tracking_image_status_t packet; - packet.point_x = point_x; - packet.point_y = point_y; - packet.radius = radius; - packet.rec_top_x = rec_top_x; - packet.rec_top_y = rec_top_y; - packet.rec_bottom_x = rec_bottom_x; - packet.rec_bottom_y = rec_bottom_y; - packet.tracking_status = tracking_status; - packet.tracking_mode = tracking_mode; - packet.target_data = target_data; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS_MIN_LEN, MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS_LEN, MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS_CRC); -} - -/** - * @brief Pack a camera_tracking_image_status message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param tracking_status Current tracking status - * @param tracking_mode Current tracking mode - * @param target_data Defines location of target data - * @param point_x Current tracked point x value if CAMERA_TRACKING_MODE_POINT (normalized 0..1, 0 is left, 1 is right), NAN if unknown - * @param point_y Current tracked point y value if CAMERA_TRACKING_MODE_POINT (normalized 0..1, 0 is top, 1 is bottom), NAN if unknown - * @param radius Current tracked radius if CAMERA_TRACKING_MODE_POINT (normalized 0..1, 0 is image left, 1 is image right), NAN if unknown - * @param rec_top_x Current tracked rectangle top x value if CAMERA_TRACKING_MODE_RECTANGLE (normalized 0..1, 0 is left, 1 is right), NAN if unknown - * @param rec_top_y Current tracked rectangle top y value if CAMERA_TRACKING_MODE_RECTANGLE (normalized 0..1, 0 is top, 1 is bottom), NAN if unknown - * @param rec_bottom_x Current tracked rectangle bottom x value if CAMERA_TRACKING_MODE_RECTANGLE (normalized 0..1, 0 is left, 1 is right), NAN if unknown - * @param rec_bottom_y Current tracked rectangle bottom y value if CAMERA_TRACKING_MODE_RECTANGLE (normalized 0..1, 0 is top, 1 is bottom), NAN if unknown - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_camera_tracking_image_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t tracking_status,uint8_t tracking_mode,uint8_t target_data,float point_x,float point_y,float radius,float rec_top_x,float rec_top_y,float rec_bottom_x,float rec_bottom_y) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS_LEN]; - _mav_put_float(buf, 0, point_x); - _mav_put_float(buf, 4, point_y); - _mav_put_float(buf, 8, radius); - _mav_put_float(buf, 12, rec_top_x); - _mav_put_float(buf, 16, rec_top_y); - _mav_put_float(buf, 20, rec_bottom_x); - _mav_put_float(buf, 24, rec_bottom_y); - _mav_put_uint8_t(buf, 28, tracking_status); - _mav_put_uint8_t(buf, 29, tracking_mode); - _mav_put_uint8_t(buf, 30, target_data); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS_LEN); -#else - mavlink_camera_tracking_image_status_t packet; - packet.point_x = point_x; - packet.point_y = point_y; - packet.radius = radius; - packet.rec_top_x = rec_top_x; - packet.rec_top_y = rec_top_y; - packet.rec_bottom_x = rec_bottom_x; - packet.rec_bottom_y = rec_bottom_y; - packet.tracking_status = tracking_status; - packet.tracking_mode = tracking_mode; - packet.target_data = target_data; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS_MIN_LEN, MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS_LEN, MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS_CRC); -} - -/** - * @brief Encode a camera_tracking_image_status struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param camera_tracking_image_status C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_camera_tracking_image_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_camera_tracking_image_status_t* camera_tracking_image_status) -{ - return mavlink_msg_camera_tracking_image_status_pack(system_id, component_id, msg, camera_tracking_image_status->tracking_status, camera_tracking_image_status->tracking_mode, camera_tracking_image_status->target_data, camera_tracking_image_status->point_x, camera_tracking_image_status->point_y, camera_tracking_image_status->radius, camera_tracking_image_status->rec_top_x, camera_tracking_image_status->rec_top_y, camera_tracking_image_status->rec_bottom_x, camera_tracking_image_status->rec_bottom_y); -} - -/** - * @brief Encode a camera_tracking_image_status struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param camera_tracking_image_status C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_camera_tracking_image_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_camera_tracking_image_status_t* camera_tracking_image_status) -{ - return mavlink_msg_camera_tracking_image_status_pack_chan(system_id, component_id, chan, msg, camera_tracking_image_status->tracking_status, camera_tracking_image_status->tracking_mode, camera_tracking_image_status->target_data, camera_tracking_image_status->point_x, camera_tracking_image_status->point_y, camera_tracking_image_status->radius, camera_tracking_image_status->rec_top_x, camera_tracking_image_status->rec_top_y, camera_tracking_image_status->rec_bottom_x, camera_tracking_image_status->rec_bottom_y); -} - -/** - * @brief Send a camera_tracking_image_status message - * @param chan MAVLink channel to send the message - * - * @param tracking_status Current tracking status - * @param tracking_mode Current tracking mode - * @param target_data Defines location of target data - * @param point_x Current tracked point x value if CAMERA_TRACKING_MODE_POINT (normalized 0..1, 0 is left, 1 is right), NAN if unknown - * @param point_y Current tracked point y value if CAMERA_TRACKING_MODE_POINT (normalized 0..1, 0 is top, 1 is bottom), NAN if unknown - * @param radius Current tracked radius if CAMERA_TRACKING_MODE_POINT (normalized 0..1, 0 is image left, 1 is image right), NAN if unknown - * @param rec_top_x Current tracked rectangle top x value if CAMERA_TRACKING_MODE_RECTANGLE (normalized 0..1, 0 is left, 1 is right), NAN if unknown - * @param rec_top_y Current tracked rectangle top y value if CAMERA_TRACKING_MODE_RECTANGLE (normalized 0..1, 0 is top, 1 is bottom), NAN if unknown - * @param rec_bottom_x Current tracked rectangle bottom x value if CAMERA_TRACKING_MODE_RECTANGLE (normalized 0..1, 0 is left, 1 is right), NAN if unknown - * @param rec_bottom_y Current tracked rectangle bottom y value if CAMERA_TRACKING_MODE_RECTANGLE (normalized 0..1, 0 is top, 1 is bottom), NAN if unknown - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_camera_tracking_image_status_send(mavlink_channel_t chan, uint8_t tracking_status, uint8_t tracking_mode, uint8_t target_data, float point_x, float point_y, float radius, float rec_top_x, float rec_top_y, float rec_bottom_x, float rec_bottom_y) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS_LEN]; - _mav_put_float(buf, 0, point_x); - _mav_put_float(buf, 4, point_y); - _mav_put_float(buf, 8, radius); - _mav_put_float(buf, 12, rec_top_x); - _mav_put_float(buf, 16, rec_top_y); - _mav_put_float(buf, 20, rec_bottom_x); - _mav_put_float(buf, 24, rec_bottom_y); - _mav_put_uint8_t(buf, 28, tracking_status); - _mav_put_uint8_t(buf, 29, tracking_mode); - _mav_put_uint8_t(buf, 30, target_data); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS, buf, MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS_MIN_LEN, MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS_LEN, MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS_CRC); -#else - mavlink_camera_tracking_image_status_t packet; - packet.point_x = point_x; - packet.point_y = point_y; - packet.radius = radius; - packet.rec_top_x = rec_top_x; - packet.rec_top_y = rec_top_y; - packet.rec_bottom_x = rec_bottom_x; - packet.rec_bottom_y = rec_bottom_y; - packet.tracking_status = tracking_status; - packet.tracking_mode = tracking_mode; - packet.target_data = target_data; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS, (const char *)&packet, MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS_MIN_LEN, MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS_LEN, MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS_CRC); -#endif -} - -/** - * @brief Send a camera_tracking_image_status message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_camera_tracking_image_status_send_struct(mavlink_channel_t chan, const mavlink_camera_tracking_image_status_t* camera_tracking_image_status) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_camera_tracking_image_status_send(chan, camera_tracking_image_status->tracking_status, camera_tracking_image_status->tracking_mode, camera_tracking_image_status->target_data, camera_tracking_image_status->point_x, camera_tracking_image_status->point_y, camera_tracking_image_status->radius, camera_tracking_image_status->rec_top_x, camera_tracking_image_status->rec_top_y, camera_tracking_image_status->rec_bottom_x, camera_tracking_image_status->rec_bottom_y); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS, (const char *)camera_tracking_image_status, MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS_MIN_LEN, MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS_LEN, MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS_CRC); -#endif -} - -#if MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_camera_tracking_image_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t tracking_status, uint8_t tracking_mode, uint8_t target_data, float point_x, float point_y, float radius, float rec_top_x, float rec_top_y, float rec_bottom_x, float rec_bottom_y) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_float(buf, 0, point_x); - _mav_put_float(buf, 4, point_y); - _mav_put_float(buf, 8, radius); - _mav_put_float(buf, 12, rec_top_x); - _mav_put_float(buf, 16, rec_top_y); - _mav_put_float(buf, 20, rec_bottom_x); - _mav_put_float(buf, 24, rec_bottom_y); - _mav_put_uint8_t(buf, 28, tracking_status); - _mav_put_uint8_t(buf, 29, tracking_mode); - _mav_put_uint8_t(buf, 30, target_data); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS, buf, MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS_MIN_LEN, MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS_LEN, MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS_CRC); -#else - mavlink_camera_tracking_image_status_t *packet = (mavlink_camera_tracking_image_status_t *)msgbuf; - packet->point_x = point_x; - packet->point_y = point_y; - packet->radius = radius; - packet->rec_top_x = rec_top_x; - packet->rec_top_y = rec_top_y; - packet->rec_bottom_x = rec_bottom_x; - packet->rec_bottom_y = rec_bottom_y; - packet->tracking_status = tracking_status; - packet->tracking_mode = tracking_mode; - packet->target_data = target_data; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS, (const char *)packet, MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS_MIN_LEN, MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS_LEN, MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS_CRC); -#endif -} -#endif - -#endif - -// MESSAGE CAMERA_TRACKING_IMAGE_STATUS UNPACKING - - -/** - * @brief Get field tracking_status from camera_tracking_image_status message - * - * @return Current tracking status - */ -static inline uint8_t mavlink_msg_camera_tracking_image_status_get_tracking_status(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 28); -} - -/** - * @brief Get field tracking_mode from camera_tracking_image_status message - * - * @return Current tracking mode - */ -static inline uint8_t mavlink_msg_camera_tracking_image_status_get_tracking_mode(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 29); -} - -/** - * @brief Get field target_data from camera_tracking_image_status message - * - * @return Defines location of target data - */ -static inline uint8_t mavlink_msg_camera_tracking_image_status_get_target_data(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 30); -} - -/** - * @brief Get field point_x from camera_tracking_image_status message - * - * @return Current tracked point x value if CAMERA_TRACKING_MODE_POINT (normalized 0..1, 0 is left, 1 is right), NAN if unknown - */ -static inline float mavlink_msg_camera_tracking_image_status_get_point_x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 0); -} - -/** - * @brief Get field point_y from camera_tracking_image_status message - * - * @return Current tracked point y value if CAMERA_TRACKING_MODE_POINT (normalized 0..1, 0 is top, 1 is bottom), NAN if unknown - */ -static inline float mavlink_msg_camera_tracking_image_status_get_point_y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 4); -} - -/** - * @brief Get field radius from camera_tracking_image_status message - * - * @return Current tracked radius if CAMERA_TRACKING_MODE_POINT (normalized 0..1, 0 is image left, 1 is image right), NAN if unknown - */ -static inline float mavlink_msg_camera_tracking_image_status_get_radius(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field rec_top_x from camera_tracking_image_status message - * - * @return Current tracked rectangle top x value if CAMERA_TRACKING_MODE_RECTANGLE (normalized 0..1, 0 is left, 1 is right), NAN if unknown - */ -static inline float mavlink_msg_camera_tracking_image_status_get_rec_top_x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field rec_top_y from camera_tracking_image_status message - * - * @return Current tracked rectangle top y value if CAMERA_TRACKING_MODE_RECTANGLE (normalized 0..1, 0 is top, 1 is bottom), NAN if unknown - */ -static inline float mavlink_msg_camera_tracking_image_status_get_rec_top_y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field rec_bottom_x from camera_tracking_image_status message - * - * @return Current tracked rectangle bottom x value if CAMERA_TRACKING_MODE_RECTANGLE (normalized 0..1, 0 is left, 1 is right), NAN if unknown - */ -static inline float mavlink_msg_camera_tracking_image_status_get_rec_bottom_x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Get field rec_bottom_y from camera_tracking_image_status message - * - * @return Current tracked rectangle bottom y value if CAMERA_TRACKING_MODE_RECTANGLE (normalized 0..1, 0 is top, 1 is bottom), NAN if unknown - */ -static inline float mavlink_msg_camera_tracking_image_status_get_rec_bottom_y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Decode a camera_tracking_image_status message into a struct - * - * @param msg The message to decode - * @param camera_tracking_image_status C-struct to decode the message contents into - */ -static inline void mavlink_msg_camera_tracking_image_status_decode(const mavlink_message_t* msg, mavlink_camera_tracking_image_status_t* camera_tracking_image_status) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - camera_tracking_image_status->point_x = mavlink_msg_camera_tracking_image_status_get_point_x(msg); - camera_tracking_image_status->point_y = mavlink_msg_camera_tracking_image_status_get_point_y(msg); - camera_tracking_image_status->radius = mavlink_msg_camera_tracking_image_status_get_radius(msg); - camera_tracking_image_status->rec_top_x = mavlink_msg_camera_tracking_image_status_get_rec_top_x(msg); - camera_tracking_image_status->rec_top_y = mavlink_msg_camera_tracking_image_status_get_rec_top_y(msg); - camera_tracking_image_status->rec_bottom_x = mavlink_msg_camera_tracking_image_status_get_rec_bottom_x(msg); - camera_tracking_image_status->rec_bottom_y = mavlink_msg_camera_tracking_image_status_get_rec_bottom_y(msg); - camera_tracking_image_status->tracking_status = mavlink_msg_camera_tracking_image_status_get_tracking_status(msg); - camera_tracking_image_status->tracking_mode = mavlink_msg_camera_tracking_image_status_get_tracking_mode(msg); - camera_tracking_image_status->target_data = mavlink_msg_camera_tracking_image_status_get_target_data(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS_LEN? msg->len : MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS_LEN; - memset(camera_tracking_image_status, 0, MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS_LEN); - memcpy(camera_tracking_image_status, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_camera_trigger.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_camera_trigger.h deleted file mode 100644 index 781ef441..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_camera_trigger.h +++ /dev/null @@ -1,238 +0,0 @@ -#pragma once -// MESSAGE CAMERA_TRIGGER PACKING - -#define MAVLINK_MSG_ID_CAMERA_TRIGGER 112 - - -typedef struct __mavlink_camera_trigger_t { - uint64_t time_usec; /*< [us] Timestamp for image frame (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/ - uint32_t seq; /*< Image frame sequence*/ -} mavlink_camera_trigger_t; - -#define MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN 12 -#define MAVLINK_MSG_ID_CAMERA_TRIGGER_MIN_LEN 12 -#define MAVLINK_MSG_ID_112_LEN 12 -#define MAVLINK_MSG_ID_112_MIN_LEN 12 - -#define MAVLINK_MSG_ID_CAMERA_TRIGGER_CRC 174 -#define MAVLINK_MSG_ID_112_CRC 174 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_CAMERA_TRIGGER { \ - 112, \ - "CAMERA_TRIGGER", \ - 2, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_camera_trigger_t, time_usec) }, \ - { "seq", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_camera_trigger_t, seq) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_CAMERA_TRIGGER { \ - "CAMERA_TRIGGER", \ - 2, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_camera_trigger_t, time_usec) }, \ - { "seq", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_camera_trigger_t, seq) }, \ - } \ -} -#endif - -/** - * @brief Pack a camera_trigger message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param time_usec [us] Timestamp for image frame (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @param seq Image frame sequence - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_camera_trigger_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint64_t time_usec, uint32_t seq) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint32_t(buf, 8, seq); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN); -#else - mavlink_camera_trigger_t packet; - packet.time_usec = time_usec; - packet.seq = seq; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_CAMERA_TRIGGER; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_CAMERA_TRIGGER_MIN_LEN, MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN, MAVLINK_MSG_ID_CAMERA_TRIGGER_CRC); -} - -/** - * @brief Pack a camera_trigger message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_usec [us] Timestamp for image frame (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @param seq Image frame sequence - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_camera_trigger_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint64_t time_usec,uint32_t seq) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint32_t(buf, 8, seq); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN); -#else - mavlink_camera_trigger_t packet; - packet.time_usec = time_usec; - packet.seq = seq; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_CAMERA_TRIGGER; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_CAMERA_TRIGGER_MIN_LEN, MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN, MAVLINK_MSG_ID_CAMERA_TRIGGER_CRC); -} - -/** - * @brief Encode a camera_trigger struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param camera_trigger C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_camera_trigger_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_camera_trigger_t* camera_trigger) -{ - return mavlink_msg_camera_trigger_pack(system_id, component_id, msg, camera_trigger->time_usec, camera_trigger->seq); -} - -/** - * @brief Encode a camera_trigger struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param camera_trigger C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_camera_trigger_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_camera_trigger_t* camera_trigger) -{ - return mavlink_msg_camera_trigger_pack_chan(system_id, component_id, chan, msg, camera_trigger->time_usec, camera_trigger->seq); -} - -/** - * @brief Send a camera_trigger message - * @param chan MAVLink channel to send the message - * - * @param time_usec [us] Timestamp for image frame (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @param seq Image frame sequence - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_camera_trigger_send(mavlink_channel_t chan, uint64_t time_usec, uint32_t seq) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint32_t(buf, 8, seq); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_TRIGGER, buf, MAVLINK_MSG_ID_CAMERA_TRIGGER_MIN_LEN, MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN, MAVLINK_MSG_ID_CAMERA_TRIGGER_CRC); -#else - mavlink_camera_trigger_t packet; - packet.time_usec = time_usec; - packet.seq = seq; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_TRIGGER, (const char *)&packet, MAVLINK_MSG_ID_CAMERA_TRIGGER_MIN_LEN, MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN, MAVLINK_MSG_ID_CAMERA_TRIGGER_CRC); -#endif -} - -/** - * @brief Send a camera_trigger message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_camera_trigger_send_struct(mavlink_channel_t chan, const mavlink_camera_trigger_t* camera_trigger) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_camera_trigger_send(chan, camera_trigger->time_usec, camera_trigger->seq); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_TRIGGER, (const char *)camera_trigger, MAVLINK_MSG_ID_CAMERA_TRIGGER_MIN_LEN, MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN, MAVLINK_MSG_ID_CAMERA_TRIGGER_CRC); -#endif -} - -#if MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_camera_trigger_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, uint32_t seq) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint32_t(buf, 8, seq); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_TRIGGER, buf, MAVLINK_MSG_ID_CAMERA_TRIGGER_MIN_LEN, MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN, MAVLINK_MSG_ID_CAMERA_TRIGGER_CRC); -#else - mavlink_camera_trigger_t *packet = (mavlink_camera_trigger_t *)msgbuf; - packet->time_usec = time_usec; - packet->seq = seq; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_TRIGGER, (const char *)packet, MAVLINK_MSG_ID_CAMERA_TRIGGER_MIN_LEN, MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN, MAVLINK_MSG_ID_CAMERA_TRIGGER_CRC); -#endif -} -#endif - -#endif - -// MESSAGE CAMERA_TRIGGER UNPACKING - - -/** - * @brief Get field time_usec from camera_trigger message - * - * @return [us] Timestamp for image frame (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - */ -static inline uint64_t mavlink_msg_camera_trigger_get_time_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field seq from camera_trigger message - * - * @return Image frame sequence - */ -static inline uint32_t mavlink_msg_camera_trigger_get_seq(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 8); -} - -/** - * @brief Decode a camera_trigger message into a struct - * - * @param msg The message to decode - * @param camera_trigger C-struct to decode the message contents into - */ -static inline void mavlink_msg_camera_trigger_decode(const mavlink_message_t* msg, mavlink_camera_trigger_t* camera_trigger) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - camera_trigger->time_usec = mavlink_msg_camera_trigger_get_time_usec(msg); - camera_trigger->seq = mavlink_msg_camera_trigger_get_seq(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN? msg->len : MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN; - memset(camera_trigger, 0, MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN); - memcpy(camera_trigger, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_can_filter_modify.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_can_filter_modify.h deleted file mode 100644 index b0c945e9..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_can_filter_modify.h +++ /dev/null @@ -1,330 +0,0 @@ -#pragma once -// MESSAGE CAN_FILTER_MODIFY PACKING - -#define MAVLINK_MSG_ID_CAN_FILTER_MODIFY 388 - - -typedef struct __mavlink_can_filter_modify_t { - uint16_t ids[16]; /*< filter IDs, length num_ids*/ - uint8_t target_system; /*< System ID.*/ - uint8_t target_component; /*< Component ID.*/ - uint8_t bus; /*< bus number*/ - uint8_t operation; /*< what operation to perform on the filter list. See CAN_FILTER_OP enum.*/ - uint8_t num_ids; /*< number of IDs in filter list*/ -} mavlink_can_filter_modify_t; - -#define MAVLINK_MSG_ID_CAN_FILTER_MODIFY_LEN 37 -#define MAVLINK_MSG_ID_CAN_FILTER_MODIFY_MIN_LEN 37 -#define MAVLINK_MSG_ID_388_LEN 37 -#define MAVLINK_MSG_ID_388_MIN_LEN 37 - -#define MAVLINK_MSG_ID_CAN_FILTER_MODIFY_CRC 8 -#define MAVLINK_MSG_ID_388_CRC 8 - -#define MAVLINK_MSG_CAN_FILTER_MODIFY_FIELD_IDS_LEN 16 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_CAN_FILTER_MODIFY { \ - 388, \ - "CAN_FILTER_MODIFY", \ - 6, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_can_filter_modify_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_can_filter_modify_t, target_component) }, \ - { "bus", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_can_filter_modify_t, bus) }, \ - { "operation", NULL, MAVLINK_TYPE_UINT8_T, 0, 35, offsetof(mavlink_can_filter_modify_t, operation) }, \ - { "num_ids", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_can_filter_modify_t, num_ids) }, \ - { "ids", NULL, MAVLINK_TYPE_UINT16_T, 16, 0, offsetof(mavlink_can_filter_modify_t, ids) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_CAN_FILTER_MODIFY { \ - "CAN_FILTER_MODIFY", \ - 6, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_can_filter_modify_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_can_filter_modify_t, target_component) }, \ - { "bus", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_can_filter_modify_t, bus) }, \ - { "operation", NULL, MAVLINK_TYPE_UINT8_T, 0, 35, offsetof(mavlink_can_filter_modify_t, operation) }, \ - { "num_ids", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_can_filter_modify_t, num_ids) }, \ - { "ids", NULL, MAVLINK_TYPE_UINT16_T, 16, 0, offsetof(mavlink_can_filter_modify_t, ids) }, \ - } \ -} -#endif - -/** - * @brief Pack a can_filter_modify message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID. - * @param target_component Component ID. - * @param bus bus number - * @param operation what operation to perform on the filter list. See CAN_FILTER_OP enum. - * @param num_ids number of IDs in filter list - * @param ids filter IDs, length num_ids - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_can_filter_modify_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component, uint8_t bus, uint8_t operation, uint8_t num_ids, const uint16_t *ids) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_CAN_FILTER_MODIFY_LEN]; - _mav_put_uint8_t(buf, 32, target_system); - _mav_put_uint8_t(buf, 33, target_component); - _mav_put_uint8_t(buf, 34, bus); - _mav_put_uint8_t(buf, 35, operation); - _mav_put_uint8_t(buf, 36, num_ids); - _mav_put_uint16_t_array(buf, 0, ids, 16); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CAN_FILTER_MODIFY_LEN); -#else - mavlink_can_filter_modify_t packet; - packet.target_system = target_system; - packet.target_component = target_component; - packet.bus = bus; - packet.operation = operation; - packet.num_ids = num_ids; - mav_array_memcpy(packet.ids, ids, sizeof(uint16_t)*16); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CAN_FILTER_MODIFY_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_CAN_FILTER_MODIFY; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_CAN_FILTER_MODIFY_MIN_LEN, MAVLINK_MSG_ID_CAN_FILTER_MODIFY_LEN, MAVLINK_MSG_ID_CAN_FILTER_MODIFY_CRC); -} - -/** - * @brief Pack a can_filter_modify message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID. - * @param target_component Component ID. - * @param bus bus number - * @param operation what operation to perform on the filter list. See CAN_FILTER_OP enum. - * @param num_ids number of IDs in filter list - * @param ids filter IDs, length num_ids - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_can_filter_modify_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component,uint8_t bus,uint8_t operation,uint8_t num_ids,const uint16_t *ids) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_CAN_FILTER_MODIFY_LEN]; - _mav_put_uint8_t(buf, 32, target_system); - _mav_put_uint8_t(buf, 33, target_component); - _mav_put_uint8_t(buf, 34, bus); - _mav_put_uint8_t(buf, 35, operation); - _mav_put_uint8_t(buf, 36, num_ids); - _mav_put_uint16_t_array(buf, 0, ids, 16); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CAN_FILTER_MODIFY_LEN); -#else - mavlink_can_filter_modify_t packet; - packet.target_system = target_system; - packet.target_component = target_component; - packet.bus = bus; - packet.operation = operation; - packet.num_ids = num_ids; - mav_array_memcpy(packet.ids, ids, sizeof(uint16_t)*16); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CAN_FILTER_MODIFY_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_CAN_FILTER_MODIFY; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_CAN_FILTER_MODIFY_MIN_LEN, MAVLINK_MSG_ID_CAN_FILTER_MODIFY_LEN, MAVLINK_MSG_ID_CAN_FILTER_MODIFY_CRC); -} - -/** - * @brief Encode a can_filter_modify struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param can_filter_modify C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_can_filter_modify_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_can_filter_modify_t* can_filter_modify) -{ - return mavlink_msg_can_filter_modify_pack(system_id, component_id, msg, can_filter_modify->target_system, can_filter_modify->target_component, can_filter_modify->bus, can_filter_modify->operation, can_filter_modify->num_ids, can_filter_modify->ids); -} - -/** - * @brief Encode a can_filter_modify struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param can_filter_modify C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_can_filter_modify_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_can_filter_modify_t* can_filter_modify) -{ - return mavlink_msg_can_filter_modify_pack_chan(system_id, component_id, chan, msg, can_filter_modify->target_system, can_filter_modify->target_component, can_filter_modify->bus, can_filter_modify->operation, can_filter_modify->num_ids, can_filter_modify->ids); -} - -/** - * @brief Send a can_filter_modify message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID. - * @param target_component Component ID. - * @param bus bus number - * @param operation what operation to perform on the filter list. See CAN_FILTER_OP enum. - * @param num_ids number of IDs in filter list - * @param ids filter IDs, length num_ids - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_can_filter_modify_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t bus, uint8_t operation, uint8_t num_ids, const uint16_t *ids) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_CAN_FILTER_MODIFY_LEN]; - _mav_put_uint8_t(buf, 32, target_system); - _mav_put_uint8_t(buf, 33, target_component); - _mav_put_uint8_t(buf, 34, bus); - _mav_put_uint8_t(buf, 35, operation); - _mav_put_uint8_t(buf, 36, num_ids); - _mav_put_uint16_t_array(buf, 0, ids, 16); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAN_FILTER_MODIFY, buf, MAVLINK_MSG_ID_CAN_FILTER_MODIFY_MIN_LEN, MAVLINK_MSG_ID_CAN_FILTER_MODIFY_LEN, MAVLINK_MSG_ID_CAN_FILTER_MODIFY_CRC); -#else - mavlink_can_filter_modify_t packet; - packet.target_system = target_system; - packet.target_component = target_component; - packet.bus = bus; - packet.operation = operation; - packet.num_ids = num_ids; - mav_array_memcpy(packet.ids, ids, sizeof(uint16_t)*16); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAN_FILTER_MODIFY, (const char *)&packet, MAVLINK_MSG_ID_CAN_FILTER_MODIFY_MIN_LEN, MAVLINK_MSG_ID_CAN_FILTER_MODIFY_LEN, MAVLINK_MSG_ID_CAN_FILTER_MODIFY_CRC); -#endif -} - -/** - * @brief Send a can_filter_modify message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_can_filter_modify_send_struct(mavlink_channel_t chan, const mavlink_can_filter_modify_t* can_filter_modify) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_can_filter_modify_send(chan, can_filter_modify->target_system, can_filter_modify->target_component, can_filter_modify->bus, can_filter_modify->operation, can_filter_modify->num_ids, can_filter_modify->ids); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAN_FILTER_MODIFY, (const char *)can_filter_modify, MAVLINK_MSG_ID_CAN_FILTER_MODIFY_MIN_LEN, MAVLINK_MSG_ID_CAN_FILTER_MODIFY_LEN, MAVLINK_MSG_ID_CAN_FILTER_MODIFY_CRC); -#endif -} - -#if MAVLINK_MSG_ID_CAN_FILTER_MODIFY_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_can_filter_modify_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t bus, uint8_t operation, uint8_t num_ids, const uint16_t *ids) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint8_t(buf, 32, target_system); - _mav_put_uint8_t(buf, 33, target_component); - _mav_put_uint8_t(buf, 34, bus); - _mav_put_uint8_t(buf, 35, operation); - _mav_put_uint8_t(buf, 36, num_ids); - _mav_put_uint16_t_array(buf, 0, ids, 16); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAN_FILTER_MODIFY, buf, MAVLINK_MSG_ID_CAN_FILTER_MODIFY_MIN_LEN, MAVLINK_MSG_ID_CAN_FILTER_MODIFY_LEN, MAVLINK_MSG_ID_CAN_FILTER_MODIFY_CRC); -#else - mavlink_can_filter_modify_t *packet = (mavlink_can_filter_modify_t *)msgbuf; - packet->target_system = target_system; - packet->target_component = target_component; - packet->bus = bus; - packet->operation = operation; - packet->num_ids = num_ids; - mav_array_memcpy(packet->ids, ids, sizeof(uint16_t)*16); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAN_FILTER_MODIFY, (const char *)packet, MAVLINK_MSG_ID_CAN_FILTER_MODIFY_MIN_LEN, MAVLINK_MSG_ID_CAN_FILTER_MODIFY_LEN, MAVLINK_MSG_ID_CAN_FILTER_MODIFY_CRC); -#endif -} -#endif - -#endif - -// MESSAGE CAN_FILTER_MODIFY UNPACKING - - -/** - * @brief Get field target_system from can_filter_modify message - * - * @return System ID. - */ -static inline uint8_t mavlink_msg_can_filter_modify_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 32); -} - -/** - * @brief Get field target_component from can_filter_modify message - * - * @return Component ID. - */ -static inline uint8_t mavlink_msg_can_filter_modify_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 33); -} - -/** - * @brief Get field bus from can_filter_modify message - * - * @return bus number - */ -static inline uint8_t mavlink_msg_can_filter_modify_get_bus(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 34); -} - -/** - * @brief Get field operation from can_filter_modify message - * - * @return what operation to perform on the filter list. See CAN_FILTER_OP enum. - */ -static inline uint8_t mavlink_msg_can_filter_modify_get_operation(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 35); -} - -/** - * @brief Get field num_ids from can_filter_modify message - * - * @return number of IDs in filter list - */ -static inline uint8_t mavlink_msg_can_filter_modify_get_num_ids(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 36); -} - -/** - * @brief Get field ids from can_filter_modify message - * - * @return filter IDs, length num_ids - */ -static inline uint16_t mavlink_msg_can_filter_modify_get_ids(const mavlink_message_t* msg, uint16_t *ids) -{ - return _MAV_RETURN_uint16_t_array(msg, ids, 16, 0); -} - -/** - * @brief Decode a can_filter_modify message into a struct - * - * @param msg The message to decode - * @param can_filter_modify C-struct to decode the message contents into - */ -static inline void mavlink_msg_can_filter_modify_decode(const mavlink_message_t* msg, mavlink_can_filter_modify_t* can_filter_modify) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_can_filter_modify_get_ids(msg, can_filter_modify->ids); - can_filter_modify->target_system = mavlink_msg_can_filter_modify_get_target_system(msg); - can_filter_modify->target_component = mavlink_msg_can_filter_modify_get_target_component(msg); - can_filter_modify->bus = mavlink_msg_can_filter_modify_get_bus(msg); - can_filter_modify->operation = mavlink_msg_can_filter_modify_get_operation(msg); - can_filter_modify->num_ids = mavlink_msg_can_filter_modify_get_num_ids(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_CAN_FILTER_MODIFY_LEN? msg->len : MAVLINK_MSG_ID_CAN_FILTER_MODIFY_LEN; - memset(can_filter_modify, 0, MAVLINK_MSG_ID_CAN_FILTER_MODIFY_LEN); - memcpy(can_filter_modify, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_can_frame.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_can_frame.h deleted file mode 100644 index 849f7074..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_can_frame.h +++ /dev/null @@ -1,330 +0,0 @@ -#pragma once -// MESSAGE CAN_FRAME PACKING - -#define MAVLINK_MSG_ID_CAN_FRAME 386 - - -typedef struct __mavlink_can_frame_t { - uint32_t id; /*< Frame ID*/ - uint8_t target_system; /*< System ID.*/ - uint8_t target_component; /*< Component ID.*/ - uint8_t bus; /*< Bus number*/ - uint8_t len; /*< Frame length*/ - uint8_t data[8]; /*< Frame data*/ -} mavlink_can_frame_t; - -#define MAVLINK_MSG_ID_CAN_FRAME_LEN 16 -#define MAVLINK_MSG_ID_CAN_FRAME_MIN_LEN 16 -#define MAVLINK_MSG_ID_386_LEN 16 -#define MAVLINK_MSG_ID_386_MIN_LEN 16 - -#define MAVLINK_MSG_ID_CAN_FRAME_CRC 132 -#define MAVLINK_MSG_ID_386_CRC 132 - -#define MAVLINK_MSG_CAN_FRAME_FIELD_DATA_LEN 8 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_CAN_FRAME { \ - 386, \ - "CAN_FRAME", \ - 6, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_can_frame_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_can_frame_t, target_component) }, \ - { "bus", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_can_frame_t, bus) }, \ - { "len", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_can_frame_t, len) }, \ - { "id", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_can_frame_t, id) }, \ - { "data", NULL, MAVLINK_TYPE_UINT8_T, 8, 8, offsetof(mavlink_can_frame_t, data) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_CAN_FRAME { \ - "CAN_FRAME", \ - 6, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_can_frame_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_can_frame_t, target_component) }, \ - { "bus", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_can_frame_t, bus) }, \ - { "len", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_can_frame_t, len) }, \ - { "id", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_can_frame_t, id) }, \ - { "data", NULL, MAVLINK_TYPE_UINT8_T, 8, 8, offsetof(mavlink_can_frame_t, data) }, \ - } \ -} -#endif - -/** - * @brief Pack a can_frame message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID. - * @param target_component Component ID. - * @param bus Bus number - * @param len Frame length - * @param id Frame ID - * @param data Frame data - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_can_frame_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component, uint8_t bus, uint8_t len, uint32_t id, const uint8_t *data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_CAN_FRAME_LEN]; - _mav_put_uint32_t(buf, 0, id); - _mav_put_uint8_t(buf, 4, target_system); - _mav_put_uint8_t(buf, 5, target_component); - _mav_put_uint8_t(buf, 6, bus); - _mav_put_uint8_t(buf, 7, len); - _mav_put_uint8_t_array(buf, 8, data, 8); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CAN_FRAME_LEN); -#else - mavlink_can_frame_t packet; - packet.id = id; - packet.target_system = target_system; - packet.target_component = target_component; - packet.bus = bus; - packet.len = len; - mav_array_memcpy(packet.data, data, sizeof(uint8_t)*8); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CAN_FRAME_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_CAN_FRAME; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_CAN_FRAME_MIN_LEN, MAVLINK_MSG_ID_CAN_FRAME_LEN, MAVLINK_MSG_ID_CAN_FRAME_CRC); -} - -/** - * @brief Pack a can_frame message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID. - * @param target_component Component ID. - * @param bus Bus number - * @param len Frame length - * @param id Frame ID - * @param data Frame data - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_can_frame_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component,uint8_t bus,uint8_t len,uint32_t id,const uint8_t *data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_CAN_FRAME_LEN]; - _mav_put_uint32_t(buf, 0, id); - _mav_put_uint8_t(buf, 4, target_system); - _mav_put_uint8_t(buf, 5, target_component); - _mav_put_uint8_t(buf, 6, bus); - _mav_put_uint8_t(buf, 7, len); - _mav_put_uint8_t_array(buf, 8, data, 8); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CAN_FRAME_LEN); -#else - mavlink_can_frame_t packet; - packet.id = id; - packet.target_system = target_system; - packet.target_component = target_component; - packet.bus = bus; - packet.len = len; - mav_array_memcpy(packet.data, data, sizeof(uint8_t)*8); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CAN_FRAME_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_CAN_FRAME; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_CAN_FRAME_MIN_LEN, MAVLINK_MSG_ID_CAN_FRAME_LEN, MAVLINK_MSG_ID_CAN_FRAME_CRC); -} - -/** - * @brief Encode a can_frame struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param can_frame C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_can_frame_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_can_frame_t* can_frame) -{ - return mavlink_msg_can_frame_pack(system_id, component_id, msg, can_frame->target_system, can_frame->target_component, can_frame->bus, can_frame->len, can_frame->id, can_frame->data); -} - -/** - * @brief Encode a can_frame struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param can_frame C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_can_frame_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_can_frame_t* can_frame) -{ - return mavlink_msg_can_frame_pack_chan(system_id, component_id, chan, msg, can_frame->target_system, can_frame->target_component, can_frame->bus, can_frame->len, can_frame->id, can_frame->data); -} - -/** - * @brief Send a can_frame message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID. - * @param target_component Component ID. - * @param bus Bus number - * @param len Frame length - * @param id Frame ID - * @param data Frame data - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_can_frame_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t bus, uint8_t len, uint32_t id, const uint8_t *data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_CAN_FRAME_LEN]; - _mav_put_uint32_t(buf, 0, id); - _mav_put_uint8_t(buf, 4, target_system); - _mav_put_uint8_t(buf, 5, target_component); - _mav_put_uint8_t(buf, 6, bus); - _mav_put_uint8_t(buf, 7, len); - _mav_put_uint8_t_array(buf, 8, data, 8); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAN_FRAME, buf, MAVLINK_MSG_ID_CAN_FRAME_MIN_LEN, MAVLINK_MSG_ID_CAN_FRAME_LEN, MAVLINK_MSG_ID_CAN_FRAME_CRC); -#else - mavlink_can_frame_t packet; - packet.id = id; - packet.target_system = target_system; - packet.target_component = target_component; - packet.bus = bus; - packet.len = len; - mav_array_memcpy(packet.data, data, sizeof(uint8_t)*8); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAN_FRAME, (const char *)&packet, MAVLINK_MSG_ID_CAN_FRAME_MIN_LEN, MAVLINK_MSG_ID_CAN_FRAME_LEN, MAVLINK_MSG_ID_CAN_FRAME_CRC); -#endif -} - -/** - * @brief Send a can_frame message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_can_frame_send_struct(mavlink_channel_t chan, const mavlink_can_frame_t* can_frame) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_can_frame_send(chan, can_frame->target_system, can_frame->target_component, can_frame->bus, can_frame->len, can_frame->id, can_frame->data); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAN_FRAME, (const char *)can_frame, MAVLINK_MSG_ID_CAN_FRAME_MIN_LEN, MAVLINK_MSG_ID_CAN_FRAME_LEN, MAVLINK_MSG_ID_CAN_FRAME_CRC); -#endif -} - -#if MAVLINK_MSG_ID_CAN_FRAME_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_can_frame_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t bus, uint8_t len, uint32_t id, const uint8_t *data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, id); - _mav_put_uint8_t(buf, 4, target_system); - _mav_put_uint8_t(buf, 5, target_component); - _mav_put_uint8_t(buf, 6, bus); - _mav_put_uint8_t(buf, 7, len); - _mav_put_uint8_t_array(buf, 8, data, 8); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAN_FRAME, buf, MAVLINK_MSG_ID_CAN_FRAME_MIN_LEN, MAVLINK_MSG_ID_CAN_FRAME_LEN, MAVLINK_MSG_ID_CAN_FRAME_CRC); -#else - mavlink_can_frame_t *packet = (mavlink_can_frame_t *)msgbuf; - packet->id = id; - packet->target_system = target_system; - packet->target_component = target_component; - packet->bus = bus; - packet->len = len; - mav_array_memcpy(packet->data, data, sizeof(uint8_t)*8); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAN_FRAME, (const char *)packet, MAVLINK_MSG_ID_CAN_FRAME_MIN_LEN, MAVLINK_MSG_ID_CAN_FRAME_LEN, MAVLINK_MSG_ID_CAN_FRAME_CRC); -#endif -} -#endif - -#endif - -// MESSAGE CAN_FRAME UNPACKING - - -/** - * @brief Get field target_system from can_frame message - * - * @return System ID. - */ -static inline uint8_t mavlink_msg_can_frame_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 4); -} - -/** - * @brief Get field target_component from can_frame message - * - * @return Component ID. - */ -static inline uint8_t mavlink_msg_can_frame_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 5); -} - -/** - * @brief Get field bus from can_frame message - * - * @return Bus number - */ -static inline uint8_t mavlink_msg_can_frame_get_bus(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 6); -} - -/** - * @brief Get field len from can_frame message - * - * @return Frame length - */ -static inline uint8_t mavlink_msg_can_frame_get_len(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 7); -} - -/** - * @brief Get field id from can_frame message - * - * @return Frame ID - */ -static inline uint32_t mavlink_msg_can_frame_get_id(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field data from can_frame message - * - * @return Frame data - */ -static inline uint16_t mavlink_msg_can_frame_get_data(const mavlink_message_t* msg, uint8_t *data) -{ - return _MAV_RETURN_uint8_t_array(msg, data, 8, 8); -} - -/** - * @brief Decode a can_frame message into a struct - * - * @param msg The message to decode - * @param can_frame C-struct to decode the message contents into - */ -static inline void mavlink_msg_can_frame_decode(const mavlink_message_t* msg, mavlink_can_frame_t* can_frame) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - can_frame->id = mavlink_msg_can_frame_get_id(msg); - can_frame->target_system = mavlink_msg_can_frame_get_target_system(msg); - can_frame->target_component = mavlink_msg_can_frame_get_target_component(msg); - can_frame->bus = mavlink_msg_can_frame_get_bus(msg); - can_frame->len = mavlink_msg_can_frame_get_len(msg); - mavlink_msg_can_frame_get_data(msg, can_frame->data); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_CAN_FRAME_LEN? msg->len : MAVLINK_MSG_ID_CAN_FRAME_LEN; - memset(can_frame, 0, MAVLINK_MSG_ID_CAN_FRAME_LEN); - memcpy(can_frame, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_canfd_frame.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_canfd_frame.h deleted file mode 100644 index 000b11d7..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_canfd_frame.h +++ /dev/null @@ -1,330 +0,0 @@ -#pragma once -// MESSAGE CANFD_FRAME PACKING - -#define MAVLINK_MSG_ID_CANFD_FRAME 387 - - -typedef struct __mavlink_canfd_frame_t { - uint32_t id; /*< Frame ID*/ - uint8_t target_system; /*< System ID.*/ - uint8_t target_component; /*< Component ID.*/ - uint8_t bus; /*< bus number*/ - uint8_t len; /*< Frame length*/ - uint8_t data[64]; /*< Frame data*/ -} mavlink_canfd_frame_t; - -#define MAVLINK_MSG_ID_CANFD_FRAME_LEN 72 -#define MAVLINK_MSG_ID_CANFD_FRAME_MIN_LEN 72 -#define MAVLINK_MSG_ID_387_LEN 72 -#define MAVLINK_MSG_ID_387_MIN_LEN 72 - -#define MAVLINK_MSG_ID_CANFD_FRAME_CRC 4 -#define MAVLINK_MSG_ID_387_CRC 4 - -#define MAVLINK_MSG_CANFD_FRAME_FIELD_DATA_LEN 64 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_CANFD_FRAME { \ - 387, \ - "CANFD_FRAME", \ - 6, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_canfd_frame_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_canfd_frame_t, target_component) }, \ - { "bus", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_canfd_frame_t, bus) }, \ - { "len", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_canfd_frame_t, len) }, \ - { "id", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_canfd_frame_t, id) }, \ - { "data", NULL, MAVLINK_TYPE_UINT8_T, 64, 8, offsetof(mavlink_canfd_frame_t, data) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_CANFD_FRAME { \ - "CANFD_FRAME", \ - 6, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_canfd_frame_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_canfd_frame_t, target_component) }, \ - { "bus", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_canfd_frame_t, bus) }, \ - { "len", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_canfd_frame_t, len) }, \ - { "id", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_canfd_frame_t, id) }, \ - { "data", NULL, MAVLINK_TYPE_UINT8_T, 64, 8, offsetof(mavlink_canfd_frame_t, data) }, \ - } \ -} -#endif - -/** - * @brief Pack a canfd_frame message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID. - * @param target_component Component ID. - * @param bus bus number - * @param len Frame length - * @param id Frame ID - * @param data Frame data - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_canfd_frame_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component, uint8_t bus, uint8_t len, uint32_t id, const uint8_t *data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_CANFD_FRAME_LEN]; - _mav_put_uint32_t(buf, 0, id); - _mav_put_uint8_t(buf, 4, target_system); - _mav_put_uint8_t(buf, 5, target_component); - _mav_put_uint8_t(buf, 6, bus); - _mav_put_uint8_t(buf, 7, len); - _mav_put_uint8_t_array(buf, 8, data, 64); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CANFD_FRAME_LEN); -#else - mavlink_canfd_frame_t packet; - packet.id = id; - packet.target_system = target_system; - packet.target_component = target_component; - packet.bus = bus; - packet.len = len; - mav_array_memcpy(packet.data, data, sizeof(uint8_t)*64); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CANFD_FRAME_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_CANFD_FRAME; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_CANFD_FRAME_MIN_LEN, MAVLINK_MSG_ID_CANFD_FRAME_LEN, MAVLINK_MSG_ID_CANFD_FRAME_CRC); -} - -/** - * @brief Pack a canfd_frame message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID. - * @param target_component Component ID. - * @param bus bus number - * @param len Frame length - * @param id Frame ID - * @param data Frame data - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_canfd_frame_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component,uint8_t bus,uint8_t len,uint32_t id,const uint8_t *data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_CANFD_FRAME_LEN]; - _mav_put_uint32_t(buf, 0, id); - _mav_put_uint8_t(buf, 4, target_system); - _mav_put_uint8_t(buf, 5, target_component); - _mav_put_uint8_t(buf, 6, bus); - _mav_put_uint8_t(buf, 7, len); - _mav_put_uint8_t_array(buf, 8, data, 64); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CANFD_FRAME_LEN); -#else - mavlink_canfd_frame_t packet; - packet.id = id; - packet.target_system = target_system; - packet.target_component = target_component; - packet.bus = bus; - packet.len = len; - mav_array_memcpy(packet.data, data, sizeof(uint8_t)*64); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CANFD_FRAME_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_CANFD_FRAME; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_CANFD_FRAME_MIN_LEN, MAVLINK_MSG_ID_CANFD_FRAME_LEN, MAVLINK_MSG_ID_CANFD_FRAME_CRC); -} - -/** - * @brief Encode a canfd_frame struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param canfd_frame C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_canfd_frame_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_canfd_frame_t* canfd_frame) -{ - return mavlink_msg_canfd_frame_pack(system_id, component_id, msg, canfd_frame->target_system, canfd_frame->target_component, canfd_frame->bus, canfd_frame->len, canfd_frame->id, canfd_frame->data); -} - -/** - * @brief Encode a canfd_frame struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param canfd_frame C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_canfd_frame_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_canfd_frame_t* canfd_frame) -{ - return mavlink_msg_canfd_frame_pack_chan(system_id, component_id, chan, msg, canfd_frame->target_system, canfd_frame->target_component, canfd_frame->bus, canfd_frame->len, canfd_frame->id, canfd_frame->data); -} - -/** - * @brief Send a canfd_frame message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID. - * @param target_component Component ID. - * @param bus bus number - * @param len Frame length - * @param id Frame ID - * @param data Frame data - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_canfd_frame_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t bus, uint8_t len, uint32_t id, const uint8_t *data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_CANFD_FRAME_LEN]; - _mav_put_uint32_t(buf, 0, id); - _mav_put_uint8_t(buf, 4, target_system); - _mav_put_uint8_t(buf, 5, target_component); - _mav_put_uint8_t(buf, 6, bus); - _mav_put_uint8_t(buf, 7, len); - _mav_put_uint8_t_array(buf, 8, data, 64); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CANFD_FRAME, buf, MAVLINK_MSG_ID_CANFD_FRAME_MIN_LEN, MAVLINK_MSG_ID_CANFD_FRAME_LEN, MAVLINK_MSG_ID_CANFD_FRAME_CRC); -#else - mavlink_canfd_frame_t packet; - packet.id = id; - packet.target_system = target_system; - packet.target_component = target_component; - packet.bus = bus; - packet.len = len; - mav_array_memcpy(packet.data, data, sizeof(uint8_t)*64); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CANFD_FRAME, (const char *)&packet, MAVLINK_MSG_ID_CANFD_FRAME_MIN_LEN, MAVLINK_MSG_ID_CANFD_FRAME_LEN, MAVLINK_MSG_ID_CANFD_FRAME_CRC); -#endif -} - -/** - * @brief Send a canfd_frame message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_canfd_frame_send_struct(mavlink_channel_t chan, const mavlink_canfd_frame_t* canfd_frame) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_canfd_frame_send(chan, canfd_frame->target_system, canfd_frame->target_component, canfd_frame->bus, canfd_frame->len, canfd_frame->id, canfd_frame->data); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CANFD_FRAME, (const char *)canfd_frame, MAVLINK_MSG_ID_CANFD_FRAME_MIN_LEN, MAVLINK_MSG_ID_CANFD_FRAME_LEN, MAVLINK_MSG_ID_CANFD_FRAME_CRC); -#endif -} - -#if MAVLINK_MSG_ID_CANFD_FRAME_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_canfd_frame_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t bus, uint8_t len, uint32_t id, const uint8_t *data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, id); - _mav_put_uint8_t(buf, 4, target_system); - _mav_put_uint8_t(buf, 5, target_component); - _mav_put_uint8_t(buf, 6, bus); - _mav_put_uint8_t(buf, 7, len); - _mav_put_uint8_t_array(buf, 8, data, 64); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CANFD_FRAME, buf, MAVLINK_MSG_ID_CANFD_FRAME_MIN_LEN, MAVLINK_MSG_ID_CANFD_FRAME_LEN, MAVLINK_MSG_ID_CANFD_FRAME_CRC); -#else - mavlink_canfd_frame_t *packet = (mavlink_canfd_frame_t *)msgbuf; - packet->id = id; - packet->target_system = target_system; - packet->target_component = target_component; - packet->bus = bus; - packet->len = len; - mav_array_memcpy(packet->data, data, sizeof(uint8_t)*64); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CANFD_FRAME, (const char *)packet, MAVLINK_MSG_ID_CANFD_FRAME_MIN_LEN, MAVLINK_MSG_ID_CANFD_FRAME_LEN, MAVLINK_MSG_ID_CANFD_FRAME_CRC); -#endif -} -#endif - -#endif - -// MESSAGE CANFD_FRAME UNPACKING - - -/** - * @brief Get field target_system from canfd_frame message - * - * @return System ID. - */ -static inline uint8_t mavlink_msg_canfd_frame_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 4); -} - -/** - * @brief Get field target_component from canfd_frame message - * - * @return Component ID. - */ -static inline uint8_t mavlink_msg_canfd_frame_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 5); -} - -/** - * @brief Get field bus from canfd_frame message - * - * @return bus number - */ -static inline uint8_t mavlink_msg_canfd_frame_get_bus(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 6); -} - -/** - * @brief Get field len from canfd_frame message - * - * @return Frame length - */ -static inline uint8_t mavlink_msg_canfd_frame_get_len(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 7); -} - -/** - * @brief Get field id from canfd_frame message - * - * @return Frame ID - */ -static inline uint32_t mavlink_msg_canfd_frame_get_id(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field data from canfd_frame message - * - * @return Frame data - */ -static inline uint16_t mavlink_msg_canfd_frame_get_data(const mavlink_message_t* msg, uint8_t *data) -{ - return _MAV_RETURN_uint8_t_array(msg, data, 64, 8); -} - -/** - * @brief Decode a canfd_frame message into a struct - * - * @param msg The message to decode - * @param canfd_frame C-struct to decode the message contents into - */ -static inline void mavlink_msg_canfd_frame_decode(const mavlink_message_t* msg, mavlink_canfd_frame_t* canfd_frame) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - canfd_frame->id = mavlink_msg_canfd_frame_get_id(msg); - canfd_frame->target_system = mavlink_msg_canfd_frame_get_target_system(msg); - canfd_frame->target_component = mavlink_msg_canfd_frame_get_target_component(msg); - canfd_frame->bus = mavlink_msg_canfd_frame_get_bus(msg); - canfd_frame->len = mavlink_msg_canfd_frame_get_len(msg); - mavlink_msg_canfd_frame_get_data(msg, canfd_frame->data); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_CANFD_FRAME_LEN? msg->len : MAVLINK_MSG_ID_CANFD_FRAME_LEN; - memset(canfd_frame, 0, MAVLINK_MSG_ID_CANFD_FRAME_LEN); - memcpy(canfd_frame, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_cellular_config.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_cellular_config.h deleted file mode 100644 index 54fc480c..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_cellular_config.h +++ /dev/null @@ -1,383 +0,0 @@ -#pragma once -// MESSAGE CELLULAR_CONFIG PACKING - -#define MAVLINK_MSG_ID_CELLULAR_CONFIG 336 - - -typedef struct __mavlink_cellular_config_t { - uint8_t enable_lte; /*< Enable/disable LTE. 0: setting unchanged, 1: disabled, 2: enabled. Current setting when sent back as a response.*/ - uint8_t enable_pin; /*< Enable/disable PIN on the SIM card. 0: setting unchanged, 1: disabled, 2: enabled. Current setting when sent back as a response.*/ - char pin[16]; /*< PIN sent to the SIM card. Blank when PIN is disabled. Empty when message is sent back as a response.*/ - char new_pin[16]; /*< New PIN when changing the PIN. Blank to leave it unchanged. Empty when message is sent back as a response.*/ - char apn[32]; /*< Name of the cellular APN. Blank to leave it unchanged. Current APN when sent back as a response.*/ - char puk[16]; /*< Required PUK code in case the user failed to authenticate 3 times with the PIN. Empty when message is sent back as a response.*/ - uint8_t roaming; /*< Enable/disable roaming. 0: setting unchanged, 1: disabled, 2: enabled. Current setting when sent back as a response.*/ - uint8_t response; /*< Message acceptance response (sent back to GS).*/ -} mavlink_cellular_config_t; - -#define MAVLINK_MSG_ID_CELLULAR_CONFIG_LEN 84 -#define MAVLINK_MSG_ID_CELLULAR_CONFIG_MIN_LEN 84 -#define MAVLINK_MSG_ID_336_LEN 84 -#define MAVLINK_MSG_ID_336_MIN_LEN 84 - -#define MAVLINK_MSG_ID_CELLULAR_CONFIG_CRC 245 -#define MAVLINK_MSG_ID_336_CRC 245 - -#define MAVLINK_MSG_CELLULAR_CONFIG_FIELD_PIN_LEN 16 -#define MAVLINK_MSG_CELLULAR_CONFIG_FIELD_NEW_PIN_LEN 16 -#define MAVLINK_MSG_CELLULAR_CONFIG_FIELD_APN_LEN 32 -#define MAVLINK_MSG_CELLULAR_CONFIG_FIELD_PUK_LEN 16 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_CELLULAR_CONFIG { \ - 336, \ - "CELLULAR_CONFIG", \ - 8, \ - { { "enable_lte", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_cellular_config_t, enable_lte) }, \ - { "enable_pin", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_cellular_config_t, enable_pin) }, \ - { "pin", NULL, MAVLINK_TYPE_CHAR, 16, 2, offsetof(mavlink_cellular_config_t, pin) }, \ - { "new_pin", NULL, MAVLINK_TYPE_CHAR, 16, 18, offsetof(mavlink_cellular_config_t, new_pin) }, \ - { "apn", NULL, MAVLINK_TYPE_CHAR, 32, 34, offsetof(mavlink_cellular_config_t, apn) }, \ - { "puk", NULL, MAVLINK_TYPE_CHAR, 16, 66, offsetof(mavlink_cellular_config_t, puk) }, \ - { "roaming", NULL, MAVLINK_TYPE_UINT8_T, 0, 82, offsetof(mavlink_cellular_config_t, roaming) }, \ - { "response", NULL, MAVLINK_TYPE_UINT8_T, 0, 83, offsetof(mavlink_cellular_config_t, response) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_CELLULAR_CONFIG { \ - "CELLULAR_CONFIG", \ - 8, \ - { { "enable_lte", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_cellular_config_t, enable_lte) }, \ - { "enable_pin", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_cellular_config_t, enable_pin) }, \ - { "pin", NULL, MAVLINK_TYPE_CHAR, 16, 2, offsetof(mavlink_cellular_config_t, pin) }, \ - { "new_pin", NULL, MAVLINK_TYPE_CHAR, 16, 18, offsetof(mavlink_cellular_config_t, new_pin) }, \ - { "apn", NULL, MAVLINK_TYPE_CHAR, 32, 34, offsetof(mavlink_cellular_config_t, apn) }, \ - { "puk", NULL, MAVLINK_TYPE_CHAR, 16, 66, offsetof(mavlink_cellular_config_t, puk) }, \ - { "roaming", NULL, MAVLINK_TYPE_UINT8_T, 0, 82, offsetof(mavlink_cellular_config_t, roaming) }, \ - { "response", NULL, MAVLINK_TYPE_UINT8_T, 0, 83, offsetof(mavlink_cellular_config_t, response) }, \ - } \ -} -#endif - -/** - * @brief Pack a cellular_config message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param enable_lte Enable/disable LTE. 0: setting unchanged, 1: disabled, 2: enabled. Current setting when sent back as a response. - * @param enable_pin Enable/disable PIN on the SIM card. 0: setting unchanged, 1: disabled, 2: enabled. Current setting when sent back as a response. - * @param pin PIN sent to the SIM card. Blank when PIN is disabled. Empty when message is sent back as a response. - * @param new_pin New PIN when changing the PIN. Blank to leave it unchanged. Empty when message is sent back as a response. - * @param apn Name of the cellular APN. Blank to leave it unchanged. Current APN when sent back as a response. - * @param puk Required PUK code in case the user failed to authenticate 3 times with the PIN. Empty when message is sent back as a response. - * @param roaming Enable/disable roaming. 0: setting unchanged, 1: disabled, 2: enabled. Current setting when sent back as a response. - * @param response Message acceptance response (sent back to GS). - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_cellular_config_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t enable_lte, uint8_t enable_pin, const char *pin, const char *new_pin, const char *apn, const char *puk, uint8_t roaming, uint8_t response) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_CELLULAR_CONFIG_LEN]; - _mav_put_uint8_t(buf, 0, enable_lte); - _mav_put_uint8_t(buf, 1, enable_pin); - _mav_put_uint8_t(buf, 82, roaming); - _mav_put_uint8_t(buf, 83, response); - _mav_put_char_array(buf, 2, pin, 16); - _mav_put_char_array(buf, 18, new_pin, 16); - _mav_put_char_array(buf, 34, apn, 32); - _mav_put_char_array(buf, 66, puk, 16); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CELLULAR_CONFIG_LEN); -#else - mavlink_cellular_config_t packet; - packet.enable_lte = enable_lte; - packet.enable_pin = enable_pin; - packet.roaming = roaming; - packet.response = response; - mav_array_memcpy(packet.pin, pin, sizeof(char)*16); - mav_array_memcpy(packet.new_pin, new_pin, sizeof(char)*16); - mav_array_memcpy(packet.apn, apn, sizeof(char)*32); - mav_array_memcpy(packet.puk, puk, sizeof(char)*16); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CELLULAR_CONFIG_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_CELLULAR_CONFIG; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_CELLULAR_CONFIG_MIN_LEN, MAVLINK_MSG_ID_CELLULAR_CONFIG_LEN, MAVLINK_MSG_ID_CELLULAR_CONFIG_CRC); -} - -/** - * @brief Pack a cellular_config message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param enable_lte Enable/disable LTE. 0: setting unchanged, 1: disabled, 2: enabled. Current setting when sent back as a response. - * @param enable_pin Enable/disable PIN on the SIM card. 0: setting unchanged, 1: disabled, 2: enabled. Current setting when sent back as a response. - * @param pin PIN sent to the SIM card. Blank when PIN is disabled. Empty when message is sent back as a response. - * @param new_pin New PIN when changing the PIN. Blank to leave it unchanged. Empty when message is sent back as a response. - * @param apn Name of the cellular APN. Blank to leave it unchanged. Current APN when sent back as a response. - * @param puk Required PUK code in case the user failed to authenticate 3 times with the PIN. Empty when message is sent back as a response. - * @param roaming Enable/disable roaming. 0: setting unchanged, 1: disabled, 2: enabled. Current setting when sent back as a response. - * @param response Message acceptance response (sent back to GS). - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_cellular_config_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t enable_lte,uint8_t enable_pin,const char *pin,const char *new_pin,const char *apn,const char *puk,uint8_t roaming,uint8_t response) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_CELLULAR_CONFIG_LEN]; - _mav_put_uint8_t(buf, 0, enable_lte); - _mav_put_uint8_t(buf, 1, enable_pin); - _mav_put_uint8_t(buf, 82, roaming); - _mav_put_uint8_t(buf, 83, response); - _mav_put_char_array(buf, 2, pin, 16); - _mav_put_char_array(buf, 18, new_pin, 16); - _mav_put_char_array(buf, 34, apn, 32); - _mav_put_char_array(buf, 66, puk, 16); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CELLULAR_CONFIG_LEN); -#else - mavlink_cellular_config_t packet; - packet.enable_lte = enable_lte; - packet.enable_pin = enable_pin; - packet.roaming = roaming; - packet.response = response; - mav_array_memcpy(packet.pin, pin, sizeof(char)*16); - mav_array_memcpy(packet.new_pin, new_pin, sizeof(char)*16); - mav_array_memcpy(packet.apn, apn, sizeof(char)*32); - mav_array_memcpy(packet.puk, puk, sizeof(char)*16); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CELLULAR_CONFIG_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_CELLULAR_CONFIG; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_CELLULAR_CONFIG_MIN_LEN, MAVLINK_MSG_ID_CELLULAR_CONFIG_LEN, MAVLINK_MSG_ID_CELLULAR_CONFIG_CRC); -} - -/** - * @brief Encode a cellular_config struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param cellular_config C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_cellular_config_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_cellular_config_t* cellular_config) -{ - return mavlink_msg_cellular_config_pack(system_id, component_id, msg, cellular_config->enable_lte, cellular_config->enable_pin, cellular_config->pin, cellular_config->new_pin, cellular_config->apn, cellular_config->puk, cellular_config->roaming, cellular_config->response); -} - -/** - * @brief Encode a cellular_config struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param cellular_config C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_cellular_config_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_cellular_config_t* cellular_config) -{ - return mavlink_msg_cellular_config_pack_chan(system_id, component_id, chan, msg, cellular_config->enable_lte, cellular_config->enable_pin, cellular_config->pin, cellular_config->new_pin, cellular_config->apn, cellular_config->puk, cellular_config->roaming, cellular_config->response); -} - -/** - * @brief Send a cellular_config message - * @param chan MAVLink channel to send the message - * - * @param enable_lte Enable/disable LTE. 0: setting unchanged, 1: disabled, 2: enabled. Current setting when sent back as a response. - * @param enable_pin Enable/disable PIN on the SIM card. 0: setting unchanged, 1: disabled, 2: enabled. Current setting when sent back as a response. - * @param pin PIN sent to the SIM card. Blank when PIN is disabled. Empty when message is sent back as a response. - * @param new_pin New PIN when changing the PIN. Blank to leave it unchanged. Empty when message is sent back as a response. - * @param apn Name of the cellular APN. Blank to leave it unchanged. Current APN when sent back as a response. - * @param puk Required PUK code in case the user failed to authenticate 3 times with the PIN. Empty when message is sent back as a response. - * @param roaming Enable/disable roaming. 0: setting unchanged, 1: disabled, 2: enabled. Current setting when sent back as a response. - * @param response Message acceptance response (sent back to GS). - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_cellular_config_send(mavlink_channel_t chan, uint8_t enable_lte, uint8_t enable_pin, const char *pin, const char *new_pin, const char *apn, const char *puk, uint8_t roaming, uint8_t response) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_CELLULAR_CONFIG_LEN]; - _mav_put_uint8_t(buf, 0, enable_lte); - _mav_put_uint8_t(buf, 1, enable_pin); - _mav_put_uint8_t(buf, 82, roaming); - _mav_put_uint8_t(buf, 83, response); - _mav_put_char_array(buf, 2, pin, 16); - _mav_put_char_array(buf, 18, new_pin, 16); - _mav_put_char_array(buf, 34, apn, 32); - _mav_put_char_array(buf, 66, puk, 16); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CELLULAR_CONFIG, buf, MAVLINK_MSG_ID_CELLULAR_CONFIG_MIN_LEN, MAVLINK_MSG_ID_CELLULAR_CONFIG_LEN, MAVLINK_MSG_ID_CELLULAR_CONFIG_CRC); -#else - mavlink_cellular_config_t packet; - packet.enable_lte = enable_lte; - packet.enable_pin = enable_pin; - packet.roaming = roaming; - packet.response = response; - mav_array_memcpy(packet.pin, pin, sizeof(char)*16); - mav_array_memcpy(packet.new_pin, new_pin, sizeof(char)*16); - mav_array_memcpy(packet.apn, apn, sizeof(char)*32); - mav_array_memcpy(packet.puk, puk, sizeof(char)*16); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CELLULAR_CONFIG, (const char *)&packet, MAVLINK_MSG_ID_CELLULAR_CONFIG_MIN_LEN, MAVLINK_MSG_ID_CELLULAR_CONFIG_LEN, MAVLINK_MSG_ID_CELLULAR_CONFIG_CRC); -#endif -} - -/** - * @brief Send a cellular_config message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_cellular_config_send_struct(mavlink_channel_t chan, const mavlink_cellular_config_t* cellular_config) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_cellular_config_send(chan, cellular_config->enable_lte, cellular_config->enable_pin, cellular_config->pin, cellular_config->new_pin, cellular_config->apn, cellular_config->puk, cellular_config->roaming, cellular_config->response); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CELLULAR_CONFIG, (const char *)cellular_config, MAVLINK_MSG_ID_CELLULAR_CONFIG_MIN_LEN, MAVLINK_MSG_ID_CELLULAR_CONFIG_LEN, MAVLINK_MSG_ID_CELLULAR_CONFIG_CRC); -#endif -} - -#if MAVLINK_MSG_ID_CELLULAR_CONFIG_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_cellular_config_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t enable_lte, uint8_t enable_pin, const char *pin, const char *new_pin, const char *apn, const char *puk, uint8_t roaming, uint8_t response) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint8_t(buf, 0, enable_lte); - _mav_put_uint8_t(buf, 1, enable_pin); - _mav_put_uint8_t(buf, 82, roaming); - _mav_put_uint8_t(buf, 83, response); - _mav_put_char_array(buf, 2, pin, 16); - _mav_put_char_array(buf, 18, new_pin, 16); - _mav_put_char_array(buf, 34, apn, 32); - _mav_put_char_array(buf, 66, puk, 16); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CELLULAR_CONFIG, buf, MAVLINK_MSG_ID_CELLULAR_CONFIG_MIN_LEN, MAVLINK_MSG_ID_CELLULAR_CONFIG_LEN, MAVLINK_MSG_ID_CELLULAR_CONFIG_CRC); -#else - mavlink_cellular_config_t *packet = (mavlink_cellular_config_t *)msgbuf; - packet->enable_lte = enable_lte; - packet->enable_pin = enable_pin; - packet->roaming = roaming; - packet->response = response; - mav_array_memcpy(packet->pin, pin, sizeof(char)*16); - mav_array_memcpy(packet->new_pin, new_pin, sizeof(char)*16); - mav_array_memcpy(packet->apn, apn, sizeof(char)*32); - mav_array_memcpy(packet->puk, puk, sizeof(char)*16); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CELLULAR_CONFIG, (const char *)packet, MAVLINK_MSG_ID_CELLULAR_CONFIG_MIN_LEN, MAVLINK_MSG_ID_CELLULAR_CONFIG_LEN, MAVLINK_MSG_ID_CELLULAR_CONFIG_CRC); -#endif -} -#endif - -#endif - -// MESSAGE CELLULAR_CONFIG UNPACKING - - -/** - * @brief Get field enable_lte from cellular_config message - * - * @return Enable/disable LTE. 0: setting unchanged, 1: disabled, 2: enabled. Current setting when sent back as a response. - */ -static inline uint8_t mavlink_msg_cellular_config_get_enable_lte(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 0); -} - -/** - * @brief Get field enable_pin from cellular_config message - * - * @return Enable/disable PIN on the SIM card. 0: setting unchanged, 1: disabled, 2: enabled. Current setting when sent back as a response. - */ -static inline uint8_t mavlink_msg_cellular_config_get_enable_pin(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 1); -} - -/** - * @brief Get field pin from cellular_config message - * - * @return PIN sent to the SIM card. Blank when PIN is disabled. Empty when message is sent back as a response. - */ -static inline uint16_t mavlink_msg_cellular_config_get_pin(const mavlink_message_t* msg, char *pin) -{ - return _MAV_RETURN_char_array(msg, pin, 16, 2); -} - -/** - * @brief Get field new_pin from cellular_config message - * - * @return New PIN when changing the PIN. Blank to leave it unchanged. Empty when message is sent back as a response. - */ -static inline uint16_t mavlink_msg_cellular_config_get_new_pin(const mavlink_message_t* msg, char *new_pin) -{ - return _MAV_RETURN_char_array(msg, new_pin, 16, 18); -} - -/** - * @brief Get field apn from cellular_config message - * - * @return Name of the cellular APN. Blank to leave it unchanged. Current APN when sent back as a response. - */ -static inline uint16_t mavlink_msg_cellular_config_get_apn(const mavlink_message_t* msg, char *apn) -{ - return _MAV_RETURN_char_array(msg, apn, 32, 34); -} - -/** - * @brief Get field puk from cellular_config message - * - * @return Required PUK code in case the user failed to authenticate 3 times with the PIN. Empty when message is sent back as a response. - */ -static inline uint16_t mavlink_msg_cellular_config_get_puk(const mavlink_message_t* msg, char *puk) -{ - return _MAV_RETURN_char_array(msg, puk, 16, 66); -} - -/** - * @brief Get field roaming from cellular_config message - * - * @return Enable/disable roaming. 0: setting unchanged, 1: disabled, 2: enabled. Current setting when sent back as a response. - */ -static inline uint8_t mavlink_msg_cellular_config_get_roaming(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 82); -} - -/** - * @brief Get field response from cellular_config message - * - * @return Message acceptance response (sent back to GS). - */ -static inline uint8_t mavlink_msg_cellular_config_get_response(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 83); -} - -/** - * @brief Decode a cellular_config message into a struct - * - * @param msg The message to decode - * @param cellular_config C-struct to decode the message contents into - */ -static inline void mavlink_msg_cellular_config_decode(const mavlink_message_t* msg, mavlink_cellular_config_t* cellular_config) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - cellular_config->enable_lte = mavlink_msg_cellular_config_get_enable_lte(msg); - cellular_config->enable_pin = mavlink_msg_cellular_config_get_enable_pin(msg); - mavlink_msg_cellular_config_get_pin(msg, cellular_config->pin); - mavlink_msg_cellular_config_get_new_pin(msg, cellular_config->new_pin); - mavlink_msg_cellular_config_get_apn(msg, cellular_config->apn); - mavlink_msg_cellular_config_get_puk(msg, cellular_config->puk); - cellular_config->roaming = mavlink_msg_cellular_config_get_roaming(msg); - cellular_config->response = mavlink_msg_cellular_config_get_response(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_CELLULAR_CONFIG_LEN? msg->len : MAVLINK_MSG_ID_CELLULAR_CONFIG_LEN; - memset(cellular_config, 0, MAVLINK_MSG_ID_CELLULAR_CONFIG_LEN); - memcpy(cellular_config, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_cellular_status.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_cellular_status.h deleted file mode 100644 index 1528ad5f..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_cellular_status.h +++ /dev/null @@ -1,363 +0,0 @@ -#pragma once -// MESSAGE CELLULAR_STATUS PACKING - -#define MAVLINK_MSG_ID_CELLULAR_STATUS 334 - - -typedef struct __mavlink_cellular_status_t { - uint16_t mcc; /*< Mobile country code. If unknown, set to UINT16_MAX*/ - uint16_t mnc; /*< Mobile network code. If unknown, set to UINT16_MAX*/ - uint16_t lac; /*< Location area code. If unknown, set to 0*/ - uint8_t status; /*< Cellular modem status*/ - uint8_t failure_reason; /*< Failure reason when status in in CELLULAR_STATUS_FLAG_FAILED*/ - uint8_t type; /*< Cellular network radio type: gsm, cdma, lte...*/ - uint8_t quality; /*< Signal quality in percent. If unknown, set to UINT8_MAX*/ -} mavlink_cellular_status_t; - -#define MAVLINK_MSG_ID_CELLULAR_STATUS_LEN 10 -#define MAVLINK_MSG_ID_CELLULAR_STATUS_MIN_LEN 10 -#define MAVLINK_MSG_ID_334_LEN 10 -#define MAVLINK_MSG_ID_334_MIN_LEN 10 - -#define MAVLINK_MSG_ID_CELLULAR_STATUS_CRC 72 -#define MAVLINK_MSG_ID_334_CRC 72 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_CELLULAR_STATUS { \ - 334, \ - "CELLULAR_STATUS", \ - 7, \ - { { "status", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_cellular_status_t, status) }, \ - { "failure_reason", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_cellular_status_t, failure_reason) }, \ - { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_cellular_status_t, type) }, \ - { "quality", NULL, MAVLINK_TYPE_UINT8_T, 0, 9, offsetof(mavlink_cellular_status_t, quality) }, \ - { "mcc", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_cellular_status_t, mcc) }, \ - { "mnc", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_cellular_status_t, mnc) }, \ - { "lac", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_cellular_status_t, lac) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_CELLULAR_STATUS { \ - "CELLULAR_STATUS", \ - 7, \ - { { "status", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_cellular_status_t, status) }, \ - { "failure_reason", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_cellular_status_t, failure_reason) }, \ - { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_cellular_status_t, type) }, \ - { "quality", NULL, MAVLINK_TYPE_UINT8_T, 0, 9, offsetof(mavlink_cellular_status_t, quality) }, \ - { "mcc", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_cellular_status_t, mcc) }, \ - { "mnc", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_cellular_status_t, mnc) }, \ - { "lac", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_cellular_status_t, lac) }, \ - } \ -} -#endif - -/** - * @brief Pack a cellular_status message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param status Cellular modem status - * @param failure_reason Failure reason when status in in CELLULAR_STATUS_FLAG_FAILED - * @param type Cellular network radio type: gsm, cdma, lte... - * @param quality Signal quality in percent. If unknown, set to UINT8_MAX - * @param mcc Mobile country code. If unknown, set to UINT16_MAX - * @param mnc Mobile network code. If unknown, set to UINT16_MAX - * @param lac Location area code. If unknown, set to 0 - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_cellular_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t status, uint8_t failure_reason, uint8_t type, uint8_t quality, uint16_t mcc, uint16_t mnc, uint16_t lac) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_CELLULAR_STATUS_LEN]; - _mav_put_uint16_t(buf, 0, mcc); - _mav_put_uint16_t(buf, 2, mnc); - _mav_put_uint16_t(buf, 4, lac); - _mav_put_uint8_t(buf, 6, status); - _mav_put_uint8_t(buf, 7, failure_reason); - _mav_put_uint8_t(buf, 8, type); - _mav_put_uint8_t(buf, 9, quality); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CELLULAR_STATUS_LEN); -#else - mavlink_cellular_status_t packet; - packet.mcc = mcc; - packet.mnc = mnc; - packet.lac = lac; - packet.status = status; - packet.failure_reason = failure_reason; - packet.type = type; - packet.quality = quality; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CELLULAR_STATUS_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_CELLULAR_STATUS; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_CELLULAR_STATUS_MIN_LEN, MAVLINK_MSG_ID_CELLULAR_STATUS_LEN, MAVLINK_MSG_ID_CELLULAR_STATUS_CRC); -} - -/** - * @brief Pack a cellular_status message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param status Cellular modem status - * @param failure_reason Failure reason when status in in CELLULAR_STATUS_FLAG_FAILED - * @param type Cellular network radio type: gsm, cdma, lte... - * @param quality Signal quality in percent. If unknown, set to UINT8_MAX - * @param mcc Mobile country code. If unknown, set to UINT16_MAX - * @param mnc Mobile network code. If unknown, set to UINT16_MAX - * @param lac Location area code. If unknown, set to 0 - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_cellular_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t status,uint8_t failure_reason,uint8_t type,uint8_t quality,uint16_t mcc,uint16_t mnc,uint16_t lac) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_CELLULAR_STATUS_LEN]; - _mav_put_uint16_t(buf, 0, mcc); - _mav_put_uint16_t(buf, 2, mnc); - _mav_put_uint16_t(buf, 4, lac); - _mav_put_uint8_t(buf, 6, status); - _mav_put_uint8_t(buf, 7, failure_reason); - _mav_put_uint8_t(buf, 8, type); - _mav_put_uint8_t(buf, 9, quality); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CELLULAR_STATUS_LEN); -#else - mavlink_cellular_status_t packet; - packet.mcc = mcc; - packet.mnc = mnc; - packet.lac = lac; - packet.status = status; - packet.failure_reason = failure_reason; - packet.type = type; - packet.quality = quality; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CELLULAR_STATUS_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_CELLULAR_STATUS; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_CELLULAR_STATUS_MIN_LEN, MAVLINK_MSG_ID_CELLULAR_STATUS_LEN, MAVLINK_MSG_ID_CELLULAR_STATUS_CRC); -} - -/** - * @brief Encode a cellular_status struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param cellular_status C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_cellular_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_cellular_status_t* cellular_status) -{ - return mavlink_msg_cellular_status_pack(system_id, component_id, msg, cellular_status->status, cellular_status->failure_reason, cellular_status->type, cellular_status->quality, cellular_status->mcc, cellular_status->mnc, cellular_status->lac); -} - -/** - * @brief Encode a cellular_status struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param cellular_status C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_cellular_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_cellular_status_t* cellular_status) -{ - return mavlink_msg_cellular_status_pack_chan(system_id, component_id, chan, msg, cellular_status->status, cellular_status->failure_reason, cellular_status->type, cellular_status->quality, cellular_status->mcc, cellular_status->mnc, cellular_status->lac); -} - -/** - * @brief Send a cellular_status message - * @param chan MAVLink channel to send the message - * - * @param status Cellular modem status - * @param failure_reason Failure reason when status in in CELLULAR_STATUS_FLAG_FAILED - * @param type Cellular network radio type: gsm, cdma, lte... - * @param quality Signal quality in percent. If unknown, set to UINT8_MAX - * @param mcc Mobile country code. If unknown, set to UINT16_MAX - * @param mnc Mobile network code. If unknown, set to UINT16_MAX - * @param lac Location area code. If unknown, set to 0 - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_cellular_status_send(mavlink_channel_t chan, uint8_t status, uint8_t failure_reason, uint8_t type, uint8_t quality, uint16_t mcc, uint16_t mnc, uint16_t lac) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_CELLULAR_STATUS_LEN]; - _mav_put_uint16_t(buf, 0, mcc); - _mav_put_uint16_t(buf, 2, mnc); - _mav_put_uint16_t(buf, 4, lac); - _mav_put_uint8_t(buf, 6, status); - _mav_put_uint8_t(buf, 7, failure_reason); - _mav_put_uint8_t(buf, 8, type); - _mav_put_uint8_t(buf, 9, quality); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CELLULAR_STATUS, buf, MAVLINK_MSG_ID_CELLULAR_STATUS_MIN_LEN, MAVLINK_MSG_ID_CELLULAR_STATUS_LEN, MAVLINK_MSG_ID_CELLULAR_STATUS_CRC); -#else - mavlink_cellular_status_t packet; - packet.mcc = mcc; - packet.mnc = mnc; - packet.lac = lac; - packet.status = status; - packet.failure_reason = failure_reason; - packet.type = type; - packet.quality = quality; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CELLULAR_STATUS, (const char *)&packet, MAVLINK_MSG_ID_CELLULAR_STATUS_MIN_LEN, MAVLINK_MSG_ID_CELLULAR_STATUS_LEN, MAVLINK_MSG_ID_CELLULAR_STATUS_CRC); -#endif -} - -/** - * @brief Send a cellular_status message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_cellular_status_send_struct(mavlink_channel_t chan, const mavlink_cellular_status_t* cellular_status) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_cellular_status_send(chan, cellular_status->status, cellular_status->failure_reason, cellular_status->type, cellular_status->quality, cellular_status->mcc, cellular_status->mnc, cellular_status->lac); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CELLULAR_STATUS, (const char *)cellular_status, MAVLINK_MSG_ID_CELLULAR_STATUS_MIN_LEN, MAVLINK_MSG_ID_CELLULAR_STATUS_LEN, MAVLINK_MSG_ID_CELLULAR_STATUS_CRC); -#endif -} - -#if MAVLINK_MSG_ID_CELLULAR_STATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_cellular_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t status, uint8_t failure_reason, uint8_t type, uint8_t quality, uint16_t mcc, uint16_t mnc, uint16_t lac) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint16_t(buf, 0, mcc); - _mav_put_uint16_t(buf, 2, mnc); - _mav_put_uint16_t(buf, 4, lac); - _mav_put_uint8_t(buf, 6, status); - _mav_put_uint8_t(buf, 7, failure_reason); - _mav_put_uint8_t(buf, 8, type); - _mav_put_uint8_t(buf, 9, quality); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CELLULAR_STATUS, buf, MAVLINK_MSG_ID_CELLULAR_STATUS_MIN_LEN, MAVLINK_MSG_ID_CELLULAR_STATUS_LEN, MAVLINK_MSG_ID_CELLULAR_STATUS_CRC); -#else - mavlink_cellular_status_t *packet = (mavlink_cellular_status_t *)msgbuf; - packet->mcc = mcc; - packet->mnc = mnc; - packet->lac = lac; - packet->status = status; - packet->failure_reason = failure_reason; - packet->type = type; - packet->quality = quality; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CELLULAR_STATUS, (const char *)packet, MAVLINK_MSG_ID_CELLULAR_STATUS_MIN_LEN, MAVLINK_MSG_ID_CELLULAR_STATUS_LEN, MAVLINK_MSG_ID_CELLULAR_STATUS_CRC); -#endif -} -#endif - -#endif - -// MESSAGE CELLULAR_STATUS UNPACKING - - -/** - * @brief Get field status from cellular_status message - * - * @return Cellular modem status - */ -static inline uint8_t mavlink_msg_cellular_status_get_status(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 6); -} - -/** - * @brief Get field failure_reason from cellular_status message - * - * @return Failure reason when status in in CELLULAR_STATUS_FLAG_FAILED - */ -static inline uint8_t mavlink_msg_cellular_status_get_failure_reason(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 7); -} - -/** - * @brief Get field type from cellular_status message - * - * @return Cellular network radio type: gsm, cdma, lte... - */ -static inline uint8_t mavlink_msg_cellular_status_get_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 8); -} - -/** - * @brief Get field quality from cellular_status message - * - * @return Signal quality in percent. If unknown, set to UINT8_MAX - */ -static inline uint8_t mavlink_msg_cellular_status_get_quality(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 9); -} - -/** - * @brief Get field mcc from cellular_status message - * - * @return Mobile country code. If unknown, set to UINT16_MAX - */ -static inline uint16_t mavlink_msg_cellular_status_get_mcc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 0); -} - -/** - * @brief Get field mnc from cellular_status message - * - * @return Mobile network code. If unknown, set to UINT16_MAX - */ -static inline uint16_t mavlink_msg_cellular_status_get_mnc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 2); -} - -/** - * @brief Get field lac from cellular_status message - * - * @return Location area code. If unknown, set to 0 - */ -static inline uint16_t mavlink_msg_cellular_status_get_lac(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 4); -} - -/** - * @brief Decode a cellular_status message into a struct - * - * @param msg The message to decode - * @param cellular_status C-struct to decode the message contents into - */ -static inline void mavlink_msg_cellular_status_decode(const mavlink_message_t* msg, mavlink_cellular_status_t* cellular_status) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - cellular_status->mcc = mavlink_msg_cellular_status_get_mcc(msg); - cellular_status->mnc = mavlink_msg_cellular_status_get_mnc(msg); - cellular_status->lac = mavlink_msg_cellular_status_get_lac(msg); - cellular_status->status = mavlink_msg_cellular_status_get_status(msg); - cellular_status->failure_reason = mavlink_msg_cellular_status_get_failure_reason(msg); - cellular_status->type = mavlink_msg_cellular_status_get_type(msg); - cellular_status->quality = mavlink_msg_cellular_status_get_quality(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_CELLULAR_STATUS_LEN? msg->len : MAVLINK_MSG_ID_CELLULAR_STATUS_LEN; - memset(cellular_status, 0, MAVLINK_MSG_ID_CELLULAR_STATUS_LEN); - memcpy(cellular_status, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_change_operator_control.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_change_operator_control.h deleted file mode 100644 index b36014fb..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_change_operator_control.h +++ /dev/null @@ -1,280 +0,0 @@ -#pragma once -// MESSAGE CHANGE_OPERATOR_CONTROL PACKING - -#define MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL 5 - - -typedef struct __mavlink_change_operator_control_t { - uint8_t target_system; /*< System the GCS requests control for*/ - uint8_t control_request; /*< 0: request control of this MAV, 1: Release control of this MAV*/ - uint8_t version; /*< [rad] 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch.*/ - char passkey[25]; /*< Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-"*/ -} mavlink_change_operator_control_t; - -#define MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN 28 -#define MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_MIN_LEN 28 -#define MAVLINK_MSG_ID_5_LEN 28 -#define MAVLINK_MSG_ID_5_MIN_LEN 28 - -#define MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_CRC 217 -#define MAVLINK_MSG_ID_5_CRC 217 - -#define MAVLINK_MSG_CHANGE_OPERATOR_CONTROL_FIELD_PASSKEY_LEN 25 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL { \ - 5, \ - "CHANGE_OPERATOR_CONTROL", \ - 4, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_change_operator_control_t, target_system) }, \ - { "control_request", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_change_operator_control_t, control_request) }, \ - { "version", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_change_operator_control_t, version) }, \ - { "passkey", NULL, MAVLINK_TYPE_CHAR, 25, 3, offsetof(mavlink_change_operator_control_t, passkey) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL { \ - "CHANGE_OPERATOR_CONTROL", \ - 4, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_change_operator_control_t, target_system) }, \ - { "control_request", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_change_operator_control_t, control_request) }, \ - { "version", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_change_operator_control_t, version) }, \ - { "passkey", NULL, MAVLINK_TYPE_CHAR, 25, 3, offsetof(mavlink_change_operator_control_t, passkey) }, \ - } \ -} -#endif - -/** - * @brief Pack a change_operator_control message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System the GCS requests control for - * @param control_request 0: request control of this MAV, 1: Release control of this MAV - * @param version [rad] 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch. - * @param passkey Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-" - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_change_operator_control_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t control_request, uint8_t version, const char *passkey) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN]; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, control_request); - _mav_put_uint8_t(buf, 2, version); - _mav_put_char_array(buf, 3, passkey, 25); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN); -#else - mavlink_change_operator_control_t packet; - packet.target_system = target_system; - packet.control_request = control_request; - packet.version = version; - mav_array_memcpy(packet.passkey, passkey, sizeof(char)*25); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_MIN_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_CRC); -} - -/** - * @brief Pack a change_operator_control message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System the GCS requests control for - * @param control_request 0: request control of this MAV, 1: Release control of this MAV - * @param version [rad] 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch. - * @param passkey Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-" - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_change_operator_control_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t control_request,uint8_t version,const char *passkey) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN]; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, control_request); - _mav_put_uint8_t(buf, 2, version); - _mav_put_char_array(buf, 3, passkey, 25); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN); -#else - mavlink_change_operator_control_t packet; - packet.target_system = target_system; - packet.control_request = control_request; - packet.version = version; - mav_array_memcpy(packet.passkey, passkey, sizeof(char)*25); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_MIN_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_CRC); -} - -/** - * @brief Encode a change_operator_control struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param change_operator_control C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_change_operator_control_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_change_operator_control_t* change_operator_control) -{ - return mavlink_msg_change_operator_control_pack(system_id, component_id, msg, change_operator_control->target_system, change_operator_control->control_request, change_operator_control->version, change_operator_control->passkey); -} - -/** - * @brief Encode a change_operator_control struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param change_operator_control C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_change_operator_control_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_change_operator_control_t* change_operator_control) -{ - return mavlink_msg_change_operator_control_pack_chan(system_id, component_id, chan, msg, change_operator_control->target_system, change_operator_control->control_request, change_operator_control->version, change_operator_control->passkey); -} - -/** - * @brief Send a change_operator_control message - * @param chan MAVLink channel to send the message - * - * @param target_system System the GCS requests control for - * @param control_request 0: request control of this MAV, 1: Release control of this MAV - * @param version [rad] 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch. - * @param passkey Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-" - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_change_operator_control_send(mavlink_channel_t chan, uint8_t target_system, uint8_t control_request, uint8_t version, const char *passkey) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN]; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, control_request); - _mav_put_uint8_t(buf, 2, version); - _mav_put_char_array(buf, 3, passkey, 25); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL, buf, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_MIN_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_CRC); -#else - mavlink_change_operator_control_t packet; - packet.target_system = target_system; - packet.control_request = control_request; - packet.version = version; - mav_array_memcpy(packet.passkey, passkey, sizeof(char)*25); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL, (const char *)&packet, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_MIN_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_CRC); -#endif -} - -/** - * @brief Send a change_operator_control message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_change_operator_control_send_struct(mavlink_channel_t chan, const mavlink_change_operator_control_t* change_operator_control) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_change_operator_control_send(chan, change_operator_control->target_system, change_operator_control->control_request, change_operator_control->version, change_operator_control->passkey); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL, (const char *)change_operator_control, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_MIN_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_CRC); -#endif -} - -#if MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_change_operator_control_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t control_request, uint8_t version, const char *passkey) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, control_request); - _mav_put_uint8_t(buf, 2, version); - _mav_put_char_array(buf, 3, passkey, 25); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL, buf, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_MIN_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_CRC); -#else - mavlink_change_operator_control_t *packet = (mavlink_change_operator_control_t *)msgbuf; - packet->target_system = target_system; - packet->control_request = control_request; - packet->version = version; - mav_array_memcpy(packet->passkey, passkey, sizeof(char)*25); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL, (const char *)packet, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_MIN_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_CRC); -#endif -} -#endif - -#endif - -// MESSAGE CHANGE_OPERATOR_CONTROL UNPACKING - - -/** - * @brief Get field target_system from change_operator_control message - * - * @return System the GCS requests control for - */ -static inline uint8_t mavlink_msg_change_operator_control_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 0); -} - -/** - * @brief Get field control_request from change_operator_control message - * - * @return 0: request control of this MAV, 1: Release control of this MAV - */ -static inline uint8_t mavlink_msg_change_operator_control_get_control_request(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 1); -} - -/** - * @brief Get field version from change_operator_control message - * - * @return [rad] 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch. - */ -static inline uint8_t mavlink_msg_change_operator_control_get_version(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 2); -} - -/** - * @brief Get field passkey from change_operator_control message - * - * @return Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-" - */ -static inline uint16_t mavlink_msg_change_operator_control_get_passkey(const mavlink_message_t* msg, char *passkey) -{ - return _MAV_RETURN_char_array(msg, passkey, 25, 3); -} - -/** - * @brief Decode a change_operator_control message into a struct - * - * @param msg The message to decode - * @param change_operator_control C-struct to decode the message contents into - */ -static inline void mavlink_msg_change_operator_control_decode(const mavlink_message_t* msg, mavlink_change_operator_control_t* change_operator_control) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - change_operator_control->target_system = mavlink_msg_change_operator_control_get_target_system(msg); - change_operator_control->control_request = mavlink_msg_change_operator_control_get_control_request(msg); - change_operator_control->version = mavlink_msg_change_operator_control_get_version(msg); - mavlink_msg_change_operator_control_get_passkey(msg, change_operator_control->passkey); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN? msg->len : MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN; - memset(change_operator_control, 0, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN); - memcpy(change_operator_control, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_change_operator_control_ack.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_change_operator_control_ack.h deleted file mode 100644 index 5eb073ef..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_change_operator_control_ack.h +++ /dev/null @@ -1,263 +0,0 @@ -#pragma once -// MESSAGE CHANGE_OPERATOR_CONTROL_ACK PACKING - -#define MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK 6 - - -typedef struct __mavlink_change_operator_control_ack_t { - uint8_t gcs_system_id; /*< ID of the GCS this message */ - uint8_t control_request; /*< 0: request control of this MAV, 1: Release control of this MAV*/ - uint8_t ack; /*< 0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control*/ -} mavlink_change_operator_control_ack_t; - -#define MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN 3 -#define MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_MIN_LEN 3 -#define MAVLINK_MSG_ID_6_LEN 3 -#define MAVLINK_MSG_ID_6_MIN_LEN 3 - -#define MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_CRC 104 -#define MAVLINK_MSG_ID_6_CRC 104 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL_ACK { \ - 6, \ - "CHANGE_OPERATOR_CONTROL_ACK", \ - 3, \ - { { "gcs_system_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_change_operator_control_ack_t, gcs_system_id) }, \ - { "control_request", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_change_operator_control_ack_t, control_request) }, \ - { "ack", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_change_operator_control_ack_t, ack) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL_ACK { \ - "CHANGE_OPERATOR_CONTROL_ACK", \ - 3, \ - { { "gcs_system_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_change_operator_control_ack_t, gcs_system_id) }, \ - { "control_request", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_change_operator_control_ack_t, control_request) }, \ - { "ack", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_change_operator_control_ack_t, ack) }, \ - } \ -} -#endif - -/** - * @brief Pack a change_operator_control_ack message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param gcs_system_id ID of the GCS this message - * @param control_request 0: request control of this MAV, 1: Release control of this MAV - * @param ack 0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_change_operator_control_ack_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t gcs_system_id, uint8_t control_request, uint8_t ack) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN]; - _mav_put_uint8_t(buf, 0, gcs_system_id); - _mav_put_uint8_t(buf, 1, control_request); - _mav_put_uint8_t(buf, 2, ack); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN); -#else - mavlink_change_operator_control_ack_t packet; - packet.gcs_system_id = gcs_system_id; - packet.control_request = control_request; - packet.ack = ack; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_MIN_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_CRC); -} - -/** - * @brief Pack a change_operator_control_ack message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param gcs_system_id ID of the GCS this message - * @param control_request 0: request control of this MAV, 1: Release control of this MAV - * @param ack 0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_change_operator_control_ack_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t gcs_system_id,uint8_t control_request,uint8_t ack) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN]; - _mav_put_uint8_t(buf, 0, gcs_system_id); - _mav_put_uint8_t(buf, 1, control_request); - _mav_put_uint8_t(buf, 2, ack); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN); -#else - mavlink_change_operator_control_ack_t packet; - packet.gcs_system_id = gcs_system_id; - packet.control_request = control_request; - packet.ack = ack; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_MIN_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_CRC); -} - -/** - * @brief Encode a change_operator_control_ack struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param change_operator_control_ack C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_change_operator_control_ack_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_change_operator_control_ack_t* change_operator_control_ack) -{ - return mavlink_msg_change_operator_control_ack_pack(system_id, component_id, msg, change_operator_control_ack->gcs_system_id, change_operator_control_ack->control_request, change_operator_control_ack->ack); -} - -/** - * @brief Encode a change_operator_control_ack struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param change_operator_control_ack C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_change_operator_control_ack_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_change_operator_control_ack_t* change_operator_control_ack) -{ - return mavlink_msg_change_operator_control_ack_pack_chan(system_id, component_id, chan, msg, change_operator_control_ack->gcs_system_id, change_operator_control_ack->control_request, change_operator_control_ack->ack); -} - -/** - * @brief Send a change_operator_control_ack message - * @param chan MAVLink channel to send the message - * - * @param gcs_system_id ID of the GCS this message - * @param control_request 0: request control of this MAV, 1: Release control of this MAV - * @param ack 0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_change_operator_control_ack_send(mavlink_channel_t chan, uint8_t gcs_system_id, uint8_t control_request, uint8_t ack) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN]; - _mav_put_uint8_t(buf, 0, gcs_system_id); - _mav_put_uint8_t(buf, 1, control_request); - _mav_put_uint8_t(buf, 2, ack); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK, buf, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_MIN_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_CRC); -#else - mavlink_change_operator_control_ack_t packet; - packet.gcs_system_id = gcs_system_id; - packet.control_request = control_request; - packet.ack = ack; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK, (const char *)&packet, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_MIN_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_CRC); -#endif -} - -/** - * @brief Send a change_operator_control_ack message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_change_operator_control_ack_send_struct(mavlink_channel_t chan, const mavlink_change_operator_control_ack_t* change_operator_control_ack) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_change_operator_control_ack_send(chan, change_operator_control_ack->gcs_system_id, change_operator_control_ack->control_request, change_operator_control_ack->ack); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK, (const char *)change_operator_control_ack, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_MIN_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_CRC); -#endif -} - -#if MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_change_operator_control_ack_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t gcs_system_id, uint8_t control_request, uint8_t ack) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint8_t(buf, 0, gcs_system_id); - _mav_put_uint8_t(buf, 1, control_request); - _mav_put_uint8_t(buf, 2, ack); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK, buf, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_MIN_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_CRC); -#else - mavlink_change_operator_control_ack_t *packet = (mavlink_change_operator_control_ack_t *)msgbuf; - packet->gcs_system_id = gcs_system_id; - packet->control_request = control_request; - packet->ack = ack; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK, (const char *)packet, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_MIN_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_CRC); -#endif -} -#endif - -#endif - -// MESSAGE CHANGE_OPERATOR_CONTROL_ACK UNPACKING - - -/** - * @brief Get field gcs_system_id from change_operator_control_ack message - * - * @return ID of the GCS this message - */ -static inline uint8_t mavlink_msg_change_operator_control_ack_get_gcs_system_id(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 0); -} - -/** - * @brief Get field control_request from change_operator_control_ack message - * - * @return 0: request control of this MAV, 1: Release control of this MAV - */ -static inline uint8_t mavlink_msg_change_operator_control_ack_get_control_request(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 1); -} - -/** - * @brief Get field ack from change_operator_control_ack message - * - * @return 0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control - */ -static inline uint8_t mavlink_msg_change_operator_control_ack_get_ack(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 2); -} - -/** - * @brief Decode a change_operator_control_ack message into a struct - * - * @param msg The message to decode - * @param change_operator_control_ack C-struct to decode the message contents into - */ -static inline void mavlink_msg_change_operator_control_ack_decode(const mavlink_message_t* msg, mavlink_change_operator_control_ack_t* change_operator_control_ack) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - change_operator_control_ack->gcs_system_id = mavlink_msg_change_operator_control_ack_get_gcs_system_id(msg); - change_operator_control_ack->control_request = mavlink_msg_change_operator_control_ack_get_control_request(msg); - change_operator_control_ack->ack = mavlink_msg_change_operator_control_ack_get_ack(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN? msg->len : MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN; - memset(change_operator_control_ack, 0, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN); - memcpy(change_operator_control_ack, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_collision.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_collision.h deleted file mode 100644 index 38759563..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_collision.h +++ /dev/null @@ -1,363 +0,0 @@ -#pragma once -// MESSAGE COLLISION PACKING - -#define MAVLINK_MSG_ID_COLLISION 247 - - -typedef struct __mavlink_collision_t { - uint32_t id; /*< Unique identifier, domain based on src field*/ - float time_to_minimum_delta; /*< [s] Estimated time until collision occurs*/ - float altitude_minimum_delta; /*< [m] Closest vertical distance between vehicle and object*/ - float horizontal_minimum_delta; /*< [m] Closest horizontal distance between vehicle and object*/ - uint8_t src; /*< Collision data source*/ - uint8_t action; /*< Action that is being taken to avoid this collision*/ - uint8_t threat_level; /*< How concerned the aircraft is about this collision*/ -} mavlink_collision_t; - -#define MAVLINK_MSG_ID_COLLISION_LEN 19 -#define MAVLINK_MSG_ID_COLLISION_MIN_LEN 19 -#define MAVLINK_MSG_ID_247_LEN 19 -#define MAVLINK_MSG_ID_247_MIN_LEN 19 - -#define MAVLINK_MSG_ID_COLLISION_CRC 81 -#define MAVLINK_MSG_ID_247_CRC 81 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_COLLISION { \ - 247, \ - "COLLISION", \ - 7, \ - { { "src", NULL, MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_collision_t, src) }, \ - { "id", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_collision_t, id) }, \ - { "action", NULL, MAVLINK_TYPE_UINT8_T, 0, 17, offsetof(mavlink_collision_t, action) }, \ - { "threat_level", NULL, MAVLINK_TYPE_UINT8_T, 0, 18, offsetof(mavlink_collision_t, threat_level) }, \ - { "time_to_minimum_delta", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_collision_t, time_to_minimum_delta) }, \ - { "altitude_minimum_delta", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_collision_t, altitude_minimum_delta) }, \ - { "horizontal_minimum_delta", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_collision_t, horizontal_minimum_delta) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_COLLISION { \ - "COLLISION", \ - 7, \ - { { "src", NULL, MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_collision_t, src) }, \ - { "id", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_collision_t, id) }, \ - { "action", NULL, MAVLINK_TYPE_UINT8_T, 0, 17, offsetof(mavlink_collision_t, action) }, \ - { "threat_level", NULL, MAVLINK_TYPE_UINT8_T, 0, 18, offsetof(mavlink_collision_t, threat_level) }, \ - { "time_to_minimum_delta", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_collision_t, time_to_minimum_delta) }, \ - { "altitude_minimum_delta", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_collision_t, altitude_minimum_delta) }, \ - { "horizontal_minimum_delta", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_collision_t, horizontal_minimum_delta) }, \ - } \ -} -#endif - -/** - * @brief Pack a collision message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param src Collision data source - * @param id Unique identifier, domain based on src field - * @param action Action that is being taken to avoid this collision - * @param threat_level How concerned the aircraft is about this collision - * @param time_to_minimum_delta [s] Estimated time until collision occurs - * @param altitude_minimum_delta [m] Closest vertical distance between vehicle and object - * @param horizontal_minimum_delta [m] Closest horizontal distance between vehicle and object - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_collision_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t src, uint32_t id, uint8_t action, uint8_t threat_level, float time_to_minimum_delta, float altitude_minimum_delta, float horizontal_minimum_delta) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_COLLISION_LEN]; - _mav_put_uint32_t(buf, 0, id); - _mav_put_float(buf, 4, time_to_minimum_delta); - _mav_put_float(buf, 8, altitude_minimum_delta); - _mav_put_float(buf, 12, horizontal_minimum_delta); - _mav_put_uint8_t(buf, 16, src); - _mav_put_uint8_t(buf, 17, action); - _mav_put_uint8_t(buf, 18, threat_level); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_COLLISION_LEN); -#else - mavlink_collision_t packet; - packet.id = id; - packet.time_to_minimum_delta = time_to_minimum_delta; - packet.altitude_minimum_delta = altitude_minimum_delta; - packet.horizontal_minimum_delta = horizontal_minimum_delta; - packet.src = src; - packet.action = action; - packet.threat_level = threat_level; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_COLLISION_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_COLLISION; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_COLLISION_MIN_LEN, MAVLINK_MSG_ID_COLLISION_LEN, MAVLINK_MSG_ID_COLLISION_CRC); -} - -/** - * @brief Pack a collision message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param src Collision data source - * @param id Unique identifier, domain based on src field - * @param action Action that is being taken to avoid this collision - * @param threat_level How concerned the aircraft is about this collision - * @param time_to_minimum_delta [s] Estimated time until collision occurs - * @param altitude_minimum_delta [m] Closest vertical distance between vehicle and object - * @param horizontal_minimum_delta [m] Closest horizontal distance between vehicle and object - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_collision_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t src,uint32_t id,uint8_t action,uint8_t threat_level,float time_to_minimum_delta,float altitude_minimum_delta,float horizontal_minimum_delta) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_COLLISION_LEN]; - _mav_put_uint32_t(buf, 0, id); - _mav_put_float(buf, 4, time_to_minimum_delta); - _mav_put_float(buf, 8, altitude_minimum_delta); - _mav_put_float(buf, 12, horizontal_minimum_delta); - _mav_put_uint8_t(buf, 16, src); - _mav_put_uint8_t(buf, 17, action); - _mav_put_uint8_t(buf, 18, threat_level); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_COLLISION_LEN); -#else - mavlink_collision_t packet; - packet.id = id; - packet.time_to_minimum_delta = time_to_minimum_delta; - packet.altitude_minimum_delta = altitude_minimum_delta; - packet.horizontal_minimum_delta = horizontal_minimum_delta; - packet.src = src; - packet.action = action; - packet.threat_level = threat_level; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_COLLISION_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_COLLISION; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_COLLISION_MIN_LEN, MAVLINK_MSG_ID_COLLISION_LEN, MAVLINK_MSG_ID_COLLISION_CRC); -} - -/** - * @brief Encode a collision struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param collision C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_collision_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_collision_t* collision) -{ - return mavlink_msg_collision_pack(system_id, component_id, msg, collision->src, collision->id, collision->action, collision->threat_level, collision->time_to_minimum_delta, collision->altitude_minimum_delta, collision->horizontal_minimum_delta); -} - -/** - * @brief Encode a collision struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param collision C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_collision_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_collision_t* collision) -{ - return mavlink_msg_collision_pack_chan(system_id, component_id, chan, msg, collision->src, collision->id, collision->action, collision->threat_level, collision->time_to_minimum_delta, collision->altitude_minimum_delta, collision->horizontal_minimum_delta); -} - -/** - * @brief Send a collision message - * @param chan MAVLink channel to send the message - * - * @param src Collision data source - * @param id Unique identifier, domain based on src field - * @param action Action that is being taken to avoid this collision - * @param threat_level How concerned the aircraft is about this collision - * @param time_to_minimum_delta [s] Estimated time until collision occurs - * @param altitude_minimum_delta [m] Closest vertical distance between vehicle and object - * @param horizontal_minimum_delta [m] Closest horizontal distance between vehicle and object - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_collision_send(mavlink_channel_t chan, uint8_t src, uint32_t id, uint8_t action, uint8_t threat_level, float time_to_minimum_delta, float altitude_minimum_delta, float horizontal_minimum_delta) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_COLLISION_LEN]; - _mav_put_uint32_t(buf, 0, id); - _mav_put_float(buf, 4, time_to_minimum_delta); - _mav_put_float(buf, 8, altitude_minimum_delta); - _mav_put_float(buf, 12, horizontal_minimum_delta); - _mav_put_uint8_t(buf, 16, src); - _mav_put_uint8_t(buf, 17, action); - _mav_put_uint8_t(buf, 18, threat_level); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COLLISION, buf, MAVLINK_MSG_ID_COLLISION_MIN_LEN, MAVLINK_MSG_ID_COLLISION_LEN, MAVLINK_MSG_ID_COLLISION_CRC); -#else - mavlink_collision_t packet; - packet.id = id; - packet.time_to_minimum_delta = time_to_minimum_delta; - packet.altitude_minimum_delta = altitude_minimum_delta; - packet.horizontal_minimum_delta = horizontal_minimum_delta; - packet.src = src; - packet.action = action; - packet.threat_level = threat_level; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COLLISION, (const char *)&packet, MAVLINK_MSG_ID_COLLISION_MIN_LEN, MAVLINK_MSG_ID_COLLISION_LEN, MAVLINK_MSG_ID_COLLISION_CRC); -#endif -} - -/** - * @brief Send a collision message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_collision_send_struct(mavlink_channel_t chan, const mavlink_collision_t* collision) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_collision_send(chan, collision->src, collision->id, collision->action, collision->threat_level, collision->time_to_minimum_delta, collision->altitude_minimum_delta, collision->horizontal_minimum_delta); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COLLISION, (const char *)collision, MAVLINK_MSG_ID_COLLISION_MIN_LEN, MAVLINK_MSG_ID_COLLISION_LEN, MAVLINK_MSG_ID_COLLISION_CRC); -#endif -} - -#if MAVLINK_MSG_ID_COLLISION_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_collision_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t src, uint32_t id, uint8_t action, uint8_t threat_level, float time_to_minimum_delta, float altitude_minimum_delta, float horizontal_minimum_delta) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, id); - _mav_put_float(buf, 4, time_to_minimum_delta); - _mav_put_float(buf, 8, altitude_minimum_delta); - _mav_put_float(buf, 12, horizontal_minimum_delta); - _mav_put_uint8_t(buf, 16, src); - _mav_put_uint8_t(buf, 17, action); - _mav_put_uint8_t(buf, 18, threat_level); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COLLISION, buf, MAVLINK_MSG_ID_COLLISION_MIN_LEN, MAVLINK_MSG_ID_COLLISION_LEN, MAVLINK_MSG_ID_COLLISION_CRC); -#else - mavlink_collision_t *packet = (mavlink_collision_t *)msgbuf; - packet->id = id; - packet->time_to_minimum_delta = time_to_minimum_delta; - packet->altitude_minimum_delta = altitude_minimum_delta; - packet->horizontal_minimum_delta = horizontal_minimum_delta; - packet->src = src; - packet->action = action; - packet->threat_level = threat_level; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COLLISION, (const char *)packet, MAVLINK_MSG_ID_COLLISION_MIN_LEN, MAVLINK_MSG_ID_COLLISION_LEN, MAVLINK_MSG_ID_COLLISION_CRC); -#endif -} -#endif - -#endif - -// MESSAGE COLLISION UNPACKING - - -/** - * @brief Get field src from collision message - * - * @return Collision data source - */ -static inline uint8_t mavlink_msg_collision_get_src(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 16); -} - -/** - * @brief Get field id from collision message - * - * @return Unique identifier, domain based on src field - */ -static inline uint32_t mavlink_msg_collision_get_id(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field action from collision message - * - * @return Action that is being taken to avoid this collision - */ -static inline uint8_t mavlink_msg_collision_get_action(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 17); -} - -/** - * @brief Get field threat_level from collision message - * - * @return How concerned the aircraft is about this collision - */ -static inline uint8_t mavlink_msg_collision_get_threat_level(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 18); -} - -/** - * @brief Get field time_to_minimum_delta from collision message - * - * @return [s] Estimated time until collision occurs - */ -static inline float mavlink_msg_collision_get_time_to_minimum_delta(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 4); -} - -/** - * @brief Get field altitude_minimum_delta from collision message - * - * @return [m] Closest vertical distance between vehicle and object - */ -static inline float mavlink_msg_collision_get_altitude_minimum_delta(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field horizontal_minimum_delta from collision message - * - * @return [m] Closest horizontal distance between vehicle and object - */ -static inline float mavlink_msg_collision_get_horizontal_minimum_delta(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Decode a collision message into a struct - * - * @param msg The message to decode - * @param collision C-struct to decode the message contents into - */ -static inline void mavlink_msg_collision_decode(const mavlink_message_t* msg, mavlink_collision_t* collision) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - collision->id = mavlink_msg_collision_get_id(msg); - collision->time_to_minimum_delta = mavlink_msg_collision_get_time_to_minimum_delta(msg); - collision->altitude_minimum_delta = mavlink_msg_collision_get_altitude_minimum_delta(msg); - collision->horizontal_minimum_delta = mavlink_msg_collision_get_horizontal_minimum_delta(msg); - collision->src = mavlink_msg_collision_get_src(msg); - collision->action = mavlink_msg_collision_get_action(msg); - collision->threat_level = mavlink_msg_collision_get_threat_level(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_COLLISION_LEN? msg->len : MAVLINK_MSG_ID_COLLISION_LEN; - memset(collision, 0, MAVLINK_MSG_ID_COLLISION_LEN); - memcpy(collision, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_command_ack.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_command_ack.h deleted file mode 100644 index fa524760..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_command_ack.h +++ /dev/null @@ -1,338 +0,0 @@ -#pragma once -// MESSAGE COMMAND_ACK PACKING - -#define MAVLINK_MSG_ID_COMMAND_ACK 77 - - -typedef struct __mavlink_command_ack_t { - uint16_t command; /*< Command ID (of acknowledged command).*/ - uint8_t result; /*< Result of command.*/ - uint8_t progress; /*< [%] The progress percentage when result is MAV_RESULT_IN_PROGRESS. Values: [0-100], or UINT8_MAX if the progress is unknown.*/ - int32_t result_param2; /*< Additional result information. Can be set with a command-specific enum containing command-specific error reasons for why the command might be denied. If used, the associated enum must be documented in the corresponding MAV_CMD (this enum should have a 0 value to indicate "unused" or "unknown").*/ - uint8_t target_system; /*< System ID of the target recipient. This is the ID of the system that sent the command for which this COMMAND_ACK is an acknowledgement.*/ - uint8_t target_component; /*< Component ID of the target recipient. This is the ID of the system that sent the command for which this COMMAND_ACK is an acknowledgement.*/ -} mavlink_command_ack_t; - -#define MAVLINK_MSG_ID_COMMAND_ACK_LEN 10 -#define MAVLINK_MSG_ID_COMMAND_ACK_MIN_LEN 3 -#define MAVLINK_MSG_ID_77_LEN 10 -#define MAVLINK_MSG_ID_77_MIN_LEN 3 - -#define MAVLINK_MSG_ID_COMMAND_ACK_CRC 143 -#define MAVLINK_MSG_ID_77_CRC 143 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_COMMAND_ACK { \ - 77, \ - "COMMAND_ACK", \ - 6, \ - { { "command", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_command_ack_t, command) }, \ - { "result", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_command_ack_t, result) }, \ - { "progress", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_command_ack_t, progress) }, \ - { "result_param2", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_command_ack_t, result_param2) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_command_ack_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 9, offsetof(mavlink_command_ack_t, target_component) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_COMMAND_ACK { \ - "COMMAND_ACK", \ - 6, \ - { { "command", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_command_ack_t, command) }, \ - { "result", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_command_ack_t, result) }, \ - { "progress", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_command_ack_t, progress) }, \ - { "result_param2", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_command_ack_t, result_param2) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_command_ack_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 9, offsetof(mavlink_command_ack_t, target_component) }, \ - } \ -} -#endif - -/** - * @brief Pack a command_ack message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param command Command ID (of acknowledged command). - * @param result Result of command. - * @param progress [%] The progress percentage when result is MAV_RESULT_IN_PROGRESS. Values: [0-100], or UINT8_MAX if the progress is unknown. - * @param result_param2 Additional result information. Can be set with a command-specific enum containing command-specific error reasons for why the command might be denied. If used, the associated enum must be documented in the corresponding MAV_CMD (this enum should have a 0 value to indicate "unused" or "unknown"). - * @param target_system System ID of the target recipient. This is the ID of the system that sent the command for which this COMMAND_ACK is an acknowledgement. - * @param target_component Component ID of the target recipient. This is the ID of the system that sent the command for which this COMMAND_ACK is an acknowledgement. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_command_ack_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint16_t command, uint8_t result, uint8_t progress, int32_t result_param2, uint8_t target_system, uint8_t target_component) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_COMMAND_ACK_LEN]; - _mav_put_uint16_t(buf, 0, command); - _mav_put_uint8_t(buf, 2, result); - _mav_put_uint8_t(buf, 3, progress); - _mav_put_int32_t(buf, 4, result_param2); - _mav_put_uint8_t(buf, 8, target_system); - _mav_put_uint8_t(buf, 9, target_component); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_COMMAND_ACK_LEN); -#else - mavlink_command_ack_t packet; - packet.command = command; - packet.result = result; - packet.progress = progress; - packet.result_param2 = result_param2; - packet.target_system = target_system; - packet.target_component = target_component; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_COMMAND_ACK_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_COMMAND_ACK; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_COMMAND_ACK_MIN_LEN, MAVLINK_MSG_ID_COMMAND_ACK_LEN, MAVLINK_MSG_ID_COMMAND_ACK_CRC); -} - -/** - * @brief Pack a command_ack message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param command Command ID (of acknowledged command). - * @param result Result of command. - * @param progress [%] The progress percentage when result is MAV_RESULT_IN_PROGRESS. Values: [0-100], or UINT8_MAX if the progress is unknown. - * @param result_param2 Additional result information. Can be set with a command-specific enum containing command-specific error reasons for why the command might be denied. If used, the associated enum must be documented in the corresponding MAV_CMD (this enum should have a 0 value to indicate "unused" or "unknown"). - * @param target_system System ID of the target recipient. This is the ID of the system that sent the command for which this COMMAND_ACK is an acknowledgement. - * @param target_component Component ID of the target recipient. This is the ID of the system that sent the command for which this COMMAND_ACK is an acknowledgement. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_command_ack_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint16_t command,uint8_t result,uint8_t progress,int32_t result_param2,uint8_t target_system,uint8_t target_component) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_COMMAND_ACK_LEN]; - _mav_put_uint16_t(buf, 0, command); - _mav_put_uint8_t(buf, 2, result); - _mav_put_uint8_t(buf, 3, progress); - _mav_put_int32_t(buf, 4, result_param2); - _mav_put_uint8_t(buf, 8, target_system); - _mav_put_uint8_t(buf, 9, target_component); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_COMMAND_ACK_LEN); -#else - mavlink_command_ack_t packet; - packet.command = command; - packet.result = result; - packet.progress = progress; - packet.result_param2 = result_param2; - packet.target_system = target_system; - packet.target_component = target_component; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_COMMAND_ACK_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_COMMAND_ACK; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_COMMAND_ACK_MIN_LEN, MAVLINK_MSG_ID_COMMAND_ACK_LEN, MAVLINK_MSG_ID_COMMAND_ACK_CRC); -} - -/** - * @brief Encode a command_ack struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param command_ack C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_command_ack_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_command_ack_t* command_ack) -{ - return mavlink_msg_command_ack_pack(system_id, component_id, msg, command_ack->command, command_ack->result, command_ack->progress, command_ack->result_param2, command_ack->target_system, command_ack->target_component); -} - -/** - * @brief Encode a command_ack struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param command_ack C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_command_ack_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_command_ack_t* command_ack) -{ - return mavlink_msg_command_ack_pack_chan(system_id, component_id, chan, msg, command_ack->command, command_ack->result, command_ack->progress, command_ack->result_param2, command_ack->target_system, command_ack->target_component); -} - -/** - * @brief Send a command_ack message - * @param chan MAVLink channel to send the message - * - * @param command Command ID (of acknowledged command). - * @param result Result of command. - * @param progress [%] The progress percentage when result is MAV_RESULT_IN_PROGRESS. Values: [0-100], or UINT8_MAX if the progress is unknown. - * @param result_param2 Additional result information. Can be set with a command-specific enum containing command-specific error reasons for why the command might be denied. If used, the associated enum must be documented in the corresponding MAV_CMD (this enum should have a 0 value to indicate "unused" or "unknown"). - * @param target_system System ID of the target recipient. This is the ID of the system that sent the command for which this COMMAND_ACK is an acknowledgement. - * @param target_component Component ID of the target recipient. This is the ID of the system that sent the command for which this COMMAND_ACK is an acknowledgement. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_command_ack_send(mavlink_channel_t chan, uint16_t command, uint8_t result, uint8_t progress, int32_t result_param2, uint8_t target_system, uint8_t target_component) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_COMMAND_ACK_LEN]; - _mav_put_uint16_t(buf, 0, command); - _mav_put_uint8_t(buf, 2, result); - _mav_put_uint8_t(buf, 3, progress); - _mav_put_int32_t(buf, 4, result_param2); - _mav_put_uint8_t(buf, 8, target_system); - _mav_put_uint8_t(buf, 9, target_component); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_ACK, buf, MAVLINK_MSG_ID_COMMAND_ACK_MIN_LEN, MAVLINK_MSG_ID_COMMAND_ACK_LEN, MAVLINK_MSG_ID_COMMAND_ACK_CRC); -#else - mavlink_command_ack_t packet; - packet.command = command; - packet.result = result; - packet.progress = progress; - packet.result_param2 = result_param2; - packet.target_system = target_system; - packet.target_component = target_component; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_ACK, (const char *)&packet, MAVLINK_MSG_ID_COMMAND_ACK_MIN_LEN, MAVLINK_MSG_ID_COMMAND_ACK_LEN, MAVLINK_MSG_ID_COMMAND_ACK_CRC); -#endif -} - -/** - * @brief Send a command_ack message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_command_ack_send_struct(mavlink_channel_t chan, const mavlink_command_ack_t* command_ack) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_command_ack_send(chan, command_ack->command, command_ack->result, command_ack->progress, command_ack->result_param2, command_ack->target_system, command_ack->target_component); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_ACK, (const char *)command_ack, MAVLINK_MSG_ID_COMMAND_ACK_MIN_LEN, MAVLINK_MSG_ID_COMMAND_ACK_LEN, MAVLINK_MSG_ID_COMMAND_ACK_CRC); -#endif -} - -#if MAVLINK_MSG_ID_COMMAND_ACK_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_command_ack_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint16_t command, uint8_t result, uint8_t progress, int32_t result_param2, uint8_t target_system, uint8_t target_component) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint16_t(buf, 0, command); - _mav_put_uint8_t(buf, 2, result); - _mav_put_uint8_t(buf, 3, progress); - _mav_put_int32_t(buf, 4, result_param2); - _mav_put_uint8_t(buf, 8, target_system); - _mav_put_uint8_t(buf, 9, target_component); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_ACK, buf, MAVLINK_MSG_ID_COMMAND_ACK_MIN_LEN, MAVLINK_MSG_ID_COMMAND_ACK_LEN, MAVLINK_MSG_ID_COMMAND_ACK_CRC); -#else - mavlink_command_ack_t *packet = (mavlink_command_ack_t *)msgbuf; - packet->command = command; - packet->result = result; - packet->progress = progress; - packet->result_param2 = result_param2; - packet->target_system = target_system; - packet->target_component = target_component; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_ACK, (const char *)packet, MAVLINK_MSG_ID_COMMAND_ACK_MIN_LEN, MAVLINK_MSG_ID_COMMAND_ACK_LEN, MAVLINK_MSG_ID_COMMAND_ACK_CRC); -#endif -} -#endif - -#endif - -// MESSAGE COMMAND_ACK UNPACKING - - -/** - * @brief Get field command from command_ack message - * - * @return Command ID (of acknowledged command). - */ -static inline uint16_t mavlink_msg_command_ack_get_command(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 0); -} - -/** - * @brief Get field result from command_ack message - * - * @return Result of command. - */ -static inline uint8_t mavlink_msg_command_ack_get_result(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 2); -} - -/** - * @brief Get field progress from command_ack message - * - * @return [%] The progress percentage when result is MAV_RESULT_IN_PROGRESS. Values: [0-100], or UINT8_MAX if the progress is unknown. - */ -static inline uint8_t mavlink_msg_command_ack_get_progress(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 3); -} - -/** - * @brief Get field result_param2 from command_ack message - * - * @return Additional result information. Can be set with a command-specific enum containing command-specific error reasons for why the command might be denied. If used, the associated enum must be documented in the corresponding MAV_CMD (this enum should have a 0 value to indicate "unused" or "unknown"). - */ -static inline int32_t mavlink_msg_command_ack_get_result_param2(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 4); -} - -/** - * @brief Get field target_system from command_ack message - * - * @return System ID of the target recipient. This is the ID of the system that sent the command for which this COMMAND_ACK is an acknowledgement. - */ -static inline uint8_t mavlink_msg_command_ack_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 8); -} - -/** - * @brief Get field target_component from command_ack message - * - * @return Component ID of the target recipient. This is the ID of the system that sent the command for which this COMMAND_ACK is an acknowledgement. - */ -static inline uint8_t mavlink_msg_command_ack_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 9); -} - -/** - * @brief Decode a command_ack message into a struct - * - * @param msg The message to decode - * @param command_ack C-struct to decode the message contents into - */ -static inline void mavlink_msg_command_ack_decode(const mavlink_message_t* msg, mavlink_command_ack_t* command_ack) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - command_ack->command = mavlink_msg_command_ack_get_command(msg); - command_ack->result = mavlink_msg_command_ack_get_result(msg); - command_ack->progress = mavlink_msg_command_ack_get_progress(msg); - command_ack->result_param2 = mavlink_msg_command_ack_get_result_param2(msg); - command_ack->target_system = mavlink_msg_command_ack_get_target_system(msg); - command_ack->target_component = mavlink_msg_command_ack_get_target_component(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_COMMAND_ACK_LEN? msg->len : MAVLINK_MSG_ID_COMMAND_ACK_LEN; - memset(command_ack, 0, MAVLINK_MSG_ID_COMMAND_ACK_LEN); - memcpy(command_ack, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_command_cancel.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_command_cancel.h deleted file mode 100644 index 3dc955de..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_command_cancel.h +++ /dev/null @@ -1,263 +0,0 @@ -#pragma once -// MESSAGE COMMAND_CANCEL PACKING - -#define MAVLINK_MSG_ID_COMMAND_CANCEL 80 - - -typedef struct __mavlink_command_cancel_t { - uint16_t command; /*< Command ID (of command to cancel).*/ - uint8_t target_system; /*< System executing long running command. Should not be broadcast (0).*/ - uint8_t target_component; /*< Component executing long running command.*/ -} mavlink_command_cancel_t; - -#define MAVLINK_MSG_ID_COMMAND_CANCEL_LEN 4 -#define MAVLINK_MSG_ID_COMMAND_CANCEL_MIN_LEN 4 -#define MAVLINK_MSG_ID_80_LEN 4 -#define MAVLINK_MSG_ID_80_MIN_LEN 4 - -#define MAVLINK_MSG_ID_COMMAND_CANCEL_CRC 14 -#define MAVLINK_MSG_ID_80_CRC 14 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_COMMAND_CANCEL { \ - 80, \ - "COMMAND_CANCEL", \ - 3, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_command_cancel_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_command_cancel_t, target_component) }, \ - { "command", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_command_cancel_t, command) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_COMMAND_CANCEL { \ - "COMMAND_CANCEL", \ - 3, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_command_cancel_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_command_cancel_t, target_component) }, \ - { "command", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_command_cancel_t, command) }, \ - } \ -} -#endif - -/** - * @brief Pack a command_cancel message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System executing long running command. Should not be broadcast (0). - * @param target_component Component executing long running command. - * @param command Command ID (of command to cancel). - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_command_cancel_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component, uint16_t command) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_COMMAND_CANCEL_LEN]; - _mav_put_uint16_t(buf, 0, command); - _mav_put_uint8_t(buf, 2, target_system); - _mav_put_uint8_t(buf, 3, target_component); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_COMMAND_CANCEL_LEN); -#else - mavlink_command_cancel_t packet; - packet.command = command; - packet.target_system = target_system; - packet.target_component = target_component; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_COMMAND_CANCEL_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_COMMAND_CANCEL; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_COMMAND_CANCEL_MIN_LEN, MAVLINK_MSG_ID_COMMAND_CANCEL_LEN, MAVLINK_MSG_ID_COMMAND_CANCEL_CRC); -} - -/** - * @brief Pack a command_cancel message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System executing long running command. Should not be broadcast (0). - * @param target_component Component executing long running command. - * @param command Command ID (of command to cancel). - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_command_cancel_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component,uint16_t command) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_COMMAND_CANCEL_LEN]; - _mav_put_uint16_t(buf, 0, command); - _mav_put_uint8_t(buf, 2, target_system); - _mav_put_uint8_t(buf, 3, target_component); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_COMMAND_CANCEL_LEN); -#else - mavlink_command_cancel_t packet; - packet.command = command; - packet.target_system = target_system; - packet.target_component = target_component; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_COMMAND_CANCEL_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_COMMAND_CANCEL; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_COMMAND_CANCEL_MIN_LEN, MAVLINK_MSG_ID_COMMAND_CANCEL_LEN, MAVLINK_MSG_ID_COMMAND_CANCEL_CRC); -} - -/** - * @brief Encode a command_cancel struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param command_cancel C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_command_cancel_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_command_cancel_t* command_cancel) -{ - return mavlink_msg_command_cancel_pack(system_id, component_id, msg, command_cancel->target_system, command_cancel->target_component, command_cancel->command); -} - -/** - * @brief Encode a command_cancel struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param command_cancel C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_command_cancel_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_command_cancel_t* command_cancel) -{ - return mavlink_msg_command_cancel_pack_chan(system_id, component_id, chan, msg, command_cancel->target_system, command_cancel->target_component, command_cancel->command); -} - -/** - * @brief Send a command_cancel message - * @param chan MAVLink channel to send the message - * - * @param target_system System executing long running command. Should not be broadcast (0). - * @param target_component Component executing long running command. - * @param command Command ID (of command to cancel). - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_command_cancel_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t command) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_COMMAND_CANCEL_LEN]; - _mav_put_uint16_t(buf, 0, command); - _mav_put_uint8_t(buf, 2, target_system); - _mav_put_uint8_t(buf, 3, target_component); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_CANCEL, buf, MAVLINK_MSG_ID_COMMAND_CANCEL_MIN_LEN, MAVLINK_MSG_ID_COMMAND_CANCEL_LEN, MAVLINK_MSG_ID_COMMAND_CANCEL_CRC); -#else - mavlink_command_cancel_t packet; - packet.command = command; - packet.target_system = target_system; - packet.target_component = target_component; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_CANCEL, (const char *)&packet, MAVLINK_MSG_ID_COMMAND_CANCEL_MIN_LEN, MAVLINK_MSG_ID_COMMAND_CANCEL_LEN, MAVLINK_MSG_ID_COMMAND_CANCEL_CRC); -#endif -} - -/** - * @brief Send a command_cancel message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_command_cancel_send_struct(mavlink_channel_t chan, const mavlink_command_cancel_t* command_cancel) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_command_cancel_send(chan, command_cancel->target_system, command_cancel->target_component, command_cancel->command); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_CANCEL, (const char *)command_cancel, MAVLINK_MSG_ID_COMMAND_CANCEL_MIN_LEN, MAVLINK_MSG_ID_COMMAND_CANCEL_LEN, MAVLINK_MSG_ID_COMMAND_CANCEL_CRC); -#endif -} - -#if MAVLINK_MSG_ID_COMMAND_CANCEL_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_command_cancel_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t command) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint16_t(buf, 0, command); - _mav_put_uint8_t(buf, 2, target_system); - _mav_put_uint8_t(buf, 3, target_component); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_CANCEL, buf, MAVLINK_MSG_ID_COMMAND_CANCEL_MIN_LEN, MAVLINK_MSG_ID_COMMAND_CANCEL_LEN, MAVLINK_MSG_ID_COMMAND_CANCEL_CRC); -#else - mavlink_command_cancel_t *packet = (mavlink_command_cancel_t *)msgbuf; - packet->command = command; - packet->target_system = target_system; - packet->target_component = target_component; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_CANCEL, (const char *)packet, MAVLINK_MSG_ID_COMMAND_CANCEL_MIN_LEN, MAVLINK_MSG_ID_COMMAND_CANCEL_LEN, MAVLINK_MSG_ID_COMMAND_CANCEL_CRC); -#endif -} -#endif - -#endif - -// MESSAGE COMMAND_CANCEL UNPACKING - - -/** - * @brief Get field target_system from command_cancel message - * - * @return System executing long running command. Should not be broadcast (0). - */ -static inline uint8_t mavlink_msg_command_cancel_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 2); -} - -/** - * @brief Get field target_component from command_cancel message - * - * @return Component executing long running command. - */ -static inline uint8_t mavlink_msg_command_cancel_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 3); -} - -/** - * @brief Get field command from command_cancel message - * - * @return Command ID (of command to cancel). - */ -static inline uint16_t mavlink_msg_command_cancel_get_command(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 0); -} - -/** - * @brief Decode a command_cancel message into a struct - * - * @param msg The message to decode - * @param command_cancel C-struct to decode the message contents into - */ -static inline void mavlink_msg_command_cancel_decode(const mavlink_message_t* msg, mavlink_command_cancel_t* command_cancel) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - command_cancel->command = mavlink_msg_command_cancel_get_command(msg); - command_cancel->target_system = mavlink_msg_command_cancel_get_target_system(msg); - command_cancel->target_component = mavlink_msg_command_cancel_get_target_component(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_COMMAND_CANCEL_LEN? msg->len : MAVLINK_MSG_ID_COMMAND_CANCEL_LEN; - memset(command_cancel, 0, MAVLINK_MSG_ID_COMMAND_CANCEL_LEN); - memcpy(command_cancel, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_command_int.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_command_int.h deleted file mode 100644 index 946a5b57..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_command_int.h +++ /dev/null @@ -1,513 +0,0 @@ -#pragma once -// MESSAGE COMMAND_INT PACKING - -#define MAVLINK_MSG_ID_COMMAND_INT 75 - - -typedef struct __mavlink_command_int_t { - float param1; /*< PARAM1, see MAV_CMD enum*/ - float param2; /*< PARAM2, see MAV_CMD enum*/ - float param3; /*< PARAM3, see MAV_CMD enum*/ - float param4; /*< PARAM4, see MAV_CMD enum*/ - int32_t x; /*< PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7*/ - int32_t y; /*< PARAM6 / local: y position in meters * 1e4, global: longitude in degrees * 10^7*/ - float z; /*< PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame).*/ - uint16_t command; /*< The scheduled action for the mission item.*/ - uint8_t target_system; /*< System ID*/ - uint8_t target_component; /*< Component ID*/ - uint8_t frame; /*< The coordinate system of the COMMAND.*/ - uint8_t current; /*< Not used.*/ - uint8_t autocontinue; /*< Not used (set 0).*/ -} mavlink_command_int_t; - -#define MAVLINK_MSG_ID_COMMAND_INT_LEN 35 -#define MAVLINK_MSG_ID_COMMAND_INT_MIN_LEN 35 -#define MAVLINK_MSG_ID_75_LEN 35 -#define MAVLINK_MSG_ID_75_MIN_LEN 35 - -#define MAVLINK_MSG_ID_COMMAND_INT_CRC 158 -#define MAVLINK_MSG_ID_75_CRC 158 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_COMMAND_INT { \ - 75, \ - "COMMAND_INT", \ - 13, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_command_int_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_command_int_t, target_component) }, \ - { "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_command_int_t, frame) }, \ - { "command", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_command_int_t, command) }, \ - { "current", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_command_int_t, current) }, \ - { "autocontinue", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_command_int_t, autocontinue) }, \ - { "param1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_command_int_t, param1) }, \ - { "param2", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_command_int_t, param2) }, \ - { "param3", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_command_int_t, param3) }, \ - { "param4", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_command_int_t, param4) }, \ - { "x", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_command_int_t, x) }, \ - { "y", NULL, MAVLINK_TYPE_INT32_T, 0, 20, offsetof(mavlink_command_int_t, y) }, \ - { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_command_int_t, z) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_COMMAND_INT { \ - "COMMAND_INT", \ - 13, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_command_int_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_command_int_t, target_component) }, \ - { "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_command_int_t, frame) }, \ - { "command", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_command_int_t, command) }, \ - { "current", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_command_int_t, current) }, \ - { "autocontinue", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_command_int_t, autocontinue) }, \ - { "param1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_command_int_t, param1) }, \ - { "param2", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_command_int_t, param2) }, \ - { "param3", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_command_int_t, param3) }, \ - { "param4", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_command_int_t, param4) }, \ - { "x", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_command_int_t, x) }, \ - { "y", NULL, MAVLINK_TYPE_INT32_T, 0, 20, offsetof(mavlink_command_int_t, y) }, \ - { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_command_int_t, z) }, \ - } \ -} -#endif - -/** - * @brief Pack a command_int message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID - * @param target_component Component ID - * @param frame The coordinate system of the COMMAND. - * @param command The scheduled action for the mission item. - * @param current Not used. - * @param autocontinue Not used (set 0). - * @param param1 PARAM1, see MAV_CMD enum - * @param param2 PARAM2, see MAV_CMD enum - * @param param3 PARAM3, see MAV_CMD enum - * @param param4 PARAM4, see MAV_CMD enum - * @param x PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7 - * @param y PARAM6 / local: y position in meters * 1e4, global: longitude in degrees * 10^7 - * @param z PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame). - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_command_int_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component, uint8_t frame, uint16_t command, uint8_t current, uint8_t autocontinue, float param1, float param2, float param3, float param4, int32_t x, int32_t y, float z) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_COMMAND_INT_LEN]; - _mav_put_float(buf, 0, param1); - _mav_put_float(buf, 4, param2); - _mav_put_float(buf, 8, param3); - _mav_put_float(buf, 12, param4); - _mav_put_int32_t(buf, 16, x); - _mav_put_int32_t(buf, 20, y); - _mav_put_float(buf, 24, z); - _mav_put_uint16_t(buf, 28, command); - _mav_put_uint8_t(buf, 30, target_system); - _mav_put_uint8_t(buf, 31, target_component); - _mav_put_uint8_t(buf, 32, frame); - _mav_put_uint8_t(buf, 33, current); - _mav_put_uint8_t(buf, 34, autocontinue); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_COMMAND_INT_LEN); -#else - mavlink_command_int_t packet; - packet.param1 = param1; - packet.param2 = param2; - packet.param3 = param3; - packet.param4 = param4; - packet.x = x; - packet.y = y; - packet.z = z; - packet.command = command; - packet.target_system = target_system; - packet.target_component = target_component; - packet.frame = frame; - packet.current = current; - packet.autocontinue = autocontinue; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_COMMAND_INT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_COMMAND_INT; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_COMMAND_INT_MIN_LEN, MAVLINK_MSG_ID_COMMAND_INT_LEN, MAVLINK_MSG_ID_COMMAND_INT_CRC); -} - -/** - * @brief Pack a command_int message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @param frame The coordinate system of the COMMAND. - * @param command The scheduled action for the mission item. - * @param current Not used. - * @param autocontinue Not used (set 0). - * @param param1 PARAM1, see MAV_CMD enum - * @param param2 PARAM2, see MAV_CMD enum - * @param param3 PARAM3, see MAV_CMD enum - * @param param4 PARAM4, see MAV_CMD enum - * @param x PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7 - * @param y PARAM6 / local: y position in meters * 1e4, global: longitude in degrees * 10^7 - * @param z PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame). - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_command_int_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component,uint8_t frame,uint16_t command,uint8_t current,uint8_t autocontinue,float param1,float param2,float param3,float param4,int32_t x,int32_t y,float z) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_COMMAND_INT_LEN]; - _mav_put_float(buf, 0, param1); - _mav_put_float(buf, 4, param2); - _mav_put_float(buf, 8, param3); - _mav_put_float(buf, 12, param4); - _mav_put_int32_t(buf, 16, x); - _mav_put_int32_t(buf, 20, y); - _mav_put_float(buf, 24, z); - _mav_put_uint16_t(buf, 28, command); - _mav_put_uint8_t(buf, 30, target_system); - _mav_put_uint8_t(buf, 31, target_component); - _mav_put_uint8_t(buf, 32, frame); - _mav_put_uint8_t(buf, 33, current); - _mav_put_uint8_t(buf, 34, autocontinue); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_COMMAND_INT_LEN); -#else - mavlink_command_int_t packet; - packet.param1 = param1; - packet.param2 = param2; - packet.param3 = param3; - packet.param4 = param4; - packet.x = x; - packet.y = y; - packet.z = z; - packet.command = command; - packet.target_system = target_system; - packet.target_component = target_component; - packet.frame = frame; - packet.current = current; - packet.autocontinue = autocontinue; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_COMMAND_INT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_COMMAND_INT; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_COMMAND_INT_MIN_LEN, MAVLINK_MSG_ID_COMMAND_INT_LEN, MAVLINK_MSG_ID_COMMAND_INT_CRC); -} - -/** - * @brief Encode a command_int struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param command_int C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_command_int_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_command_int_t* command_int) -{ - return mavlink_msg_command_int_pack(system_id, component_id, msg, command_int->target_system, command_int->target_component, command_int->frame, command_int->command, command_int->current, command_int->autocontinue, command_int->param1, command_int->param2, command_int->param3, command_int->param4, command_int->x, command_int->y, command_int->z); -} - -/** - * @brief Encode a command_int struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param command_int C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_command_int_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_command_int_t* command_int) -{ - return mavlink_msg_command_int_pack_chan(system_id, component_id, chan, msg, command_int->target_system, command_int->target_component, command_int->frame, command_int->command, command_int->current, command_int->autocontinue, command_int->param1, command_int->param2, command_int->param3, command_int->param4, command_int->x, command_int->y, command_int->z); -} - -/** - * @brief Send a command_int message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param target_component Component ID - * @param frame The coordinate system of the COMMAND. - * @param command The scheduled action for the mission item. - * @param current Not used. - * @param autocontinue Not used (set 0). - * @param param1 PARAM1, see MAV_CMD enum - * @param param2 PARAM2, see MAV_CMD enum - * @param param3 PARAM3, see MAV_CMD enum - * @param param4 PARAM4, see MAV_CMD enum - * @param x PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7 - * @param y PARAM6 / local: y position in meters * 1e4, global: longitude in degrees * 10^7 - * @param z PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame). - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_command_int_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t frame, uint16_t command, uint8_t current, uint8_t autocontinue, float param1, float param2, float param3, float param4, int32_t x, int32_t y, float z) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_COMMAND_INT_LEN]; - _mav_put_float(buf, 0, param1); - _mav_put_float(buf, 4, param2); - _mav_put_float(buf, 8, param3); - _mav_put_float(buf, 12, param4); - _mav_put_int32_t(buf, 16, x); - _mav_put_int32_t(buf, 20, y); - _mav_put_float(buf, 24, z); - _mav_put_uint16_t(buf, 28, command); - _mav_put_uint8_t(buf, 30, target_system); - _mav_put_uint8_t(buf, 31, target_component); - _mav_put_uint8_t(buf, 32, frame); - _mav_put_uint8_t(buf, 33, current); - _mav_put_uint8_t(buf, 34, autocontinue); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_INT, buf, MAVLINK_MSG_ID_COMMAND_INT_MIN_LEN, MAVLINK_MSG_ID_COMMAND_INT_LEN, MAVLINK_MSG_ID_COMMAND_INT_CRC); -#else - mavlink_command_int_t packet; - packet.param1 = param1; - packet.param2 = param2; - packet.param3 = param3; - packet.param4 = param4; - packet.x = x; - packet.y = y; - packet.z = z; - packet.command = command; - packet.target_system = target_system; - packet.target_component = target_component; - packet.frame = frame; - packet.current = current; - packet.autocontinue = autocontinue; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_INT, (const char *)&packet, MAVLINK_MSG_ID_COMMAND_INT_MIN_LEN, MAVLINK_MSG_ID_COMMAND_INT_LEN, MAVLINK_MSG_ID_COMMAND_INT_CRC); -#endif -} - -/** - * @brief Send a command_int message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_command_int_send_struct(mavlink_channel_t chan, const mavlink_command_int_t* command_int) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_command_int_send(chan, command_int->target_system, command_int->target_component, command_int->frame, command_int->command, command_int->current, command_int->autocontinue, command_int->param1, command_int->param2, command_int->param3, command_int->param4, command_int->x, command_int->y, command_int->z); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_INT, (const char *)command_int, MAVLINK_MSG_ID_COMMAND_INT_MIN_LEN, MAVLINK_MSG_ID_COMMAND_INT_LEN, MAVLINK_MSG_ID_COMMAND_INT_CRC); -#endif -} - -#if MAVLINK_MSG_ID_COMMAND_INT_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_command_int_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t frame, uint16_t command, uint8_t current, uint8_t autocontinue, float param1, float param2, float param3, float param4, int32_t x, int32_t y, float z) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_float(buf, 0, param1); - _mav_put_float(buf, 4, param2); - _mav_put_float(buf, 8, param3); - _mav_put_float(buf, 12, param4); - _mav_put_int32_t(buf, 16, x); - _mav_put_int32_t(buf, 20, y); - _mav_put_float(buf, 24, z); - _mav_put_uint16_t(buf, 28, command); - _mav_put_uint8_t(buf, 30, target_system); - _mav_put_uint8_t(buf, 31, target_component); - _mav_put_uint8_t(buf, 32, frame); - _mav_put_uint8_t(buf, 33, current); - _mav_put_uint8_t(buf, 34, autocontinue); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_INT, buf, MAVLINK_MSG_ID_COMMAND_INT_MIN_LEN, MAVLINK_MSG_ID_COMMAND_INT_LEN, MAVLINK_MSG_ID_COMMAND_INT_CRC); -#else - mavlink_command_int_t *packet = (mavlink_command_int_t *)msgbuf; - packet->param1 = param1; - packet->param2 = param2; - packet->param3 = param3; - packet->param4 = param4; - packet->x = x; - packet->y = y; - packet->z = z; - packet->command = command; - packet->target_system = target_system; - packet->target_component = target_component; - packet->frame = frame; - packet->current = current; - packet->autocontinue = autocontinue; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_INT, (const char *)packet, MAVLINK_MSG_ID_COMMAND_INT_MIN_LEN, MAVLINK_MSG_ID_COMMAND_INT_LEN, MAVLINK_MSG_ID_COMMAND_INT_CRC); -#endif -} -#endif - -#endif - -// MESSAGE COMMAND_INT UNPACKING - - -/** - * @brief Get field target_system from command_int message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_command_int_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 30); -} - -/** - * @brief Get field target_component from command_int message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_command_int_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 31); -} - -/** - * @brief Get field frame from command_int message - * - * @return The coordinate system of the COMMAND. - */ -static inline uint8_t mavlink_msg_command_int_get_frame(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 32); -} - -/** - * @brief Get field command from command_int message - * - * @return The scheduled action for the mission item. - */ -static inline uint16_t mavlink_msg_command_int_get_command(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 28); -} - -/** - * @brief Get field current from command_int message - * - * @return Not used. - */ -static inline uint8_t mavlink_msg_command_int_get_current(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 33); -} - -/** - * @brief Get field autocontinue from command_int message - * - * @return Not used (set 0). - */ -static inline uint8_t mavlink_msg_command_int_get_autocontinue(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 34); -} - -/** - * @brief Get field param1 from command_int message - * - * @return PARAM1, see MAV_CMD enum - */ -static inline float mavlink_msg_command_int_get_param1(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 0); -} - -/** - * @brief Get field param2 from command_int message - * - * @return PARAM2, see MAV_CMD enum - */ -static inline float mavlink_msg_command_int_get_param2(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 4); -} - -/** - * @brief Get field param3 from command_int message - * - * @return PARAM3, see MAV_CMD enum - */ -static inline float mavlink_msg_command_int_get_param3(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field param4 from command_int message - * - * @return PARAM4, see MAV_CMD enum - */ -static inline float mavlink_msg_command_int_get_param4(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field x from command_int message - * - * @return PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7 - */ -static inline int32_t mavlink_msg_command_int_get_x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 16); -} - -/** - * @brief Get field y from command_int message - * - * @return PARAM6 / local: y position in meters * 1e4, global: longitude in degrees * 10^7 - */ -static inline int32_t mavlink_msg_command_int_get_y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 20); -} - -/** - * @brief Get field z from command_int message - * - * @return PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame). - */ -static inline float mavlink_msg_command_int_get_z(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Decode a command_int message into a struct - * - * @param msg The message to decode - * @param command_int C-struct to decode the message contents into - */ -static inline void mavlink_msg_command_int_decode(const mavlink_message_t* msg, mavlink_command_int_t* command_int) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - command_int->param1 = mavlink_msg_command_int_get_param1(msg); - command_int->param2 = mavlink_msg_command_int_get_param2(msg); - command_int->param3 = mavlink_msg_command_int_get_param3(msg); - command_int->param4 = mavlink_msg_command_int_get_param4(msg); - command_int->x = mavlink_msg_command_int_get_x(msg); - command_int->y = mavlink_msg_command_int_get_y(msg); - command_int->z = mavlink_msg_command_int_get_z(msg); - command_int->command = mavlink_msg_command_int_get_command(msg); - command_int->target_system = mavlink_msg_command_int_get_target_system(msg); - command_int->target_component = mavlink_msg_command_int_get_target_component(msg); - command_int->frame = mavlink_msg_command_int_get_frame(msg); - command_int->current = mavlink_msg_command_int_get_current(msg); - command_int->autocontinue = mavlink_msg_command_int_get_autocontinue(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_COMMAND_INT_LEN? msg->len : MAVLINK_MSG_ID_COMMAND_INT_LEN; - memset(command_int, 0, MAVLINK_MSG_ID_COMMAND_INT_LEN); - memcpy(command_int, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_command_long.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_command_long.h deleted file mode 100644 index b7683778..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_command_long.h +++ /dev/null @@ -1,463 +0,0 @@ -#pragma once -// MESSAGE COMMAND_LONG PACKING - -#define MAVLINK_MSG_ID_COMMAND_LONG 76 - - -typedef struct __mavlink_command_long_t { - float param1; /*< Parameter 1 (for the specific command).*/ - float param2; /*< Parameter 2 (for the specific command).*/ - float param3; /*< Parameter 3 (for the specific command).*/ - float param4; /*< Parameter 4 (for the specific command).*/ - float param5; /*< Parameter 5 (for the specific command).*/ - float param6; /*< Parameter 6 (for the specific command).*/ - float param7; /*< Parameter 7 (for the specific command).*/ - uint16_t command; /*< Command ID (of command to send).*/ - uint8_t target_system; /*< System which should execute the command*/ - uint8_t target_component; /*< Component which should execute the command, 0 for all components*/ - uint8_t confirmation; /*< 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command)*/ -} mavlink_command_long_t; - -#define MAVLINK_MSG_ID_COMMAND_LONG_LEN 33 -#define MAVLINK_MSG_ID_COMMAND_LONG_MIN_LEN 33 -#define MAVLINK_MSG_ID_76_LEN 33 -#define MAVLINK_MSG_ID_76_MIN_LEN 33 - -#define MAVLINK_MSG_ID_COMMAND_LONG_CRC 152 -#define MAVLINK_MSG_ID_76_CRC 152 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_COMMAND_LONG { \ - 76, \ - "COMMAND_LONG", \ - 11, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_command_long_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_command_long_t, target_component) }, \ - { "command", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_command_long_t, command) }, \ - { "confirmation", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_command_long_t, confirmation) }, \ - { "param1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_command_long_t, param1) }, \ - { "param2", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_command_long_t, param2) }, \ - { "param3", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_command_long_t, param3) }, \ - { "param4", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_command_long_t, param4) }, \ - { "param5", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_command_long_t, param5) }, \ - { "param6", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_command_long_t, param6) }, \ - { "param7", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_command_long_t, param7) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_COMMAND_LONG { \ - "COMMAND_LONG", \ - 11, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_command_long_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_command_long_t, target_component) }, \ - { "command", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_command_long_t, command) }, \ - { "confirmation", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_command_long_t, confirmation) }, \ - { "param1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_command_long_t, param1) }, \ - { "param2", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_command_long_t, param2) }, \ - { "param3", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_command_long_t, param3) }, \ - { "param4", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_command_long_t, param4) }, \ - { "param5", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_command_long_t, param5) }, \ - { "param6", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_command_long_t, param6) }, \ - { "param7", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_command_long_t, param7) }, \ - } \ -} -#endif - -/** - * @brief Pack a command_long message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System which should execute the command - * @param target_component Component which should execute the command, 0 for all components - * @param command Command ID (of command to send). - * @param confirmation 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) - * @param param1 Parameter 1 (for the specific command). - * @param param2 Parameter 2 (for the specific command). - * @param param3 Parameter 3 (for the specific command). - * @param param4 Parameter 4 (for the specific command). - * @param param5 Parameter 5 (for the specific command). - * @param param6 Parameter 6 (for the specific command). - * @param param7 Parameter 7 (for the specific command). - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_command_long_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component, uint16_t command, uint8_t confirmation, float param1, float param2, float param3, float param4, float param5, float param6, float param7) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_COMMAND_LONG_LEN]; - _mav_put_float(buf, 0, param1); - _mav_put_float(buf, 4, param2); - _mav_put_float(buf, 8, param3); - _mav_put_float(buf, 12, param4); - _mav_put_float(buf, 16, param5); - _mav_put_float(buf, 20, param6); - _mav_put_float(buf, 24, param7); - _mav_put_uint16_t(buf, 28, command); - _mav_put_uint8_t(buf, 30, target_system); - _mav_put_uint8_t(buf, 31, target_component); - _mav_put_uint8_t(buf, 32, confirmation); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_COMMAND_LONG_LEN); -#else - mavlink_command_long_t packet; - packet.param1 = param1; - packet.param2 = param2; - packet.param3 = param3; - packet.param4 = param4; - packet.param5 = param5; - packet.param6 = param6; - packet.param7 = param7; - packet.command = command; - packet.target_system = target_system; - packet.target_component = target_component; - packet.confirmation = confirmation; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_COMMAND_LONG_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_COMMAND_LONG; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_COMMAND_LONG_MIN_LEN, MAVLINK_MSG_ID_COMMAND_LONG_LEN, MAVLINK_MSG_ID_COMMAND_LONG_CRC); -} - -/** - * @brief Pack a command_long message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System which should execute the command - * @param target_component Component which should execute the command, 0 for all components - * @param command Command ID (of command to send). - * @param confirmation 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) - * @param param1 Parameter 1 (for the specific command). - * @param param2 Parameter 2 (for the specific command). - * @param param3 Parameter 3 (for the specific command). - * @param param4 Parameter 4 (for the specific command). - * @param param5 Parameter 5 (for the specific command). - * @param param6 Parameter 6 (for the specific command). - * @param param7 Parameter 7 (for the specific command). - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_command_long_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component,uint16_t command,uint8_t confirmation,float param1,float param2,float param3,float param4,float param5,float param6,float param7) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_COMMAND_LONG_LEN]; - _mav_put_float(buf, 0, param1); - _mav_put_float(buf, 4, param2); - _mav_put_float(buf, 8, param3); - _mav_put_float(buf, 12, param4); - _mav_put_float(buf, 16, param5); - _mav_put_float(buf, 20, param6); - _mav_put_float(buf, 24, param7); - _mav_put_uint16_t(buf, 28, command); - _mav_put_uint8_t(buf, 30, target_system); - _mav_put_uint8_t(buf, 31, target_component); - _mav_put_uint8_t(buf, 32, confirmation); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_COMMAND_LONG_LEN); -#else - mavlink_command_long_t packet; - packet.param1 = param1; - packet.param2 = param2; - packet.param3 = param3; - packet.param4 = param4; - packet.param5 = param5; - packet.param6 = param6; - packet.param7 = param7; - packet.command = command; - packet.target_system = target_system; - packet.target_component = target_component; - packet.confirmation = confirmation; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_COMMAND_LONG_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_COMMAND_LONG; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_COMMAND_LONG_MIN_LEN, MAVLINK_MSG_ID_COMMAND_LONG_LEN, MAVLINK_MSG_ID_COMMAND_LONG_CRC); -} - -/** - * @brief Encode a command_long struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param command_long C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_command_long_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_command_long_t* command_long) -{ - return mavlink_msg_command_long_pack(system_id, component_id, msg, command_long->target_system, command_long->target_component, command_long->command, command_long->confirmation, command_long->param1, command_long->param2, command_long->param3, command_long->param4, command_long->param5, command_long->param6, command_long->param7); -} - -/** - * @brief Encode a command_long struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param command_long C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_command_long_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_command_long_t* command_long) -{ - return mavlink_msg_command_long_pack_chan(system_id, component_id, chan, msg, command_long->target_system, command_long->target_component, command_long->command, command_long->confirmation, command_long->param1, command_long->param2, command_long->param3, command_long->param4, command_long->param5, command_long->param6, command_long->param7); -} - -/** - * @brief Send a command_long message - * @param chan MAVLink channel to send the message - * - * @param target_system System which should execute the command - * @param target_component Component which should execute the command, 0 for all components - * @param command Command ID (of command to send). - * @param confirmation 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) - * @param param1 Parameter 1 (for the specific command). - * @param param2 Parameter 2 (for the specific command). - * @param param3 Parameter 3 (for the specific command). - * @param param4 Parameter 4 (for the specific command). - * @param param5 Parameter 5 (for the specific command). - * @param param6 Parameter 6 (for the specific command). - * @param param7 Parameter 7 (for the specific command). - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_command_long_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t command, uint8_t confirmation, float param1, float param2, float param3, float param4, float param5, float param6, float param7) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_COMMAND_LONG_LEN]; - _mav_put_float(buf, 0, param1); - _mav_put_float(buf, 4, param2); - _mav_put_float(buf, 8, param3); - _mav_put_float(buf, 12, param4); - _mav_put_float(buf, 16, param5); - _mav_put_float(buf, 20, param6); - _mav_put_float(buf, 24, param7); - _mav_put_uint16_t(buf, 28, command); - _mav_put_uint8_t(buf, 30, target_system); - _mav_put_uint8_t(buf, 31, target_component); - _mav_put_uint8_t(buf, 32, confirmation); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_LONG, buf, MAVLINK_MSG_ID_COMMAND_LONG_MIN_LEN, MAVLINK_MSG_ID_COMMAND_LONG_LEN, MAVLINK_MSG_ID_COMMAND_LONG_CRC); -#else - mavlink_command_long_t packet; - packet.param1 = param1; - packet.param2 = param2; - packet.param3 = param3; - packet.param4 = param4; - packet.param5 = param5; - packet.param6 = param6; - packet.param7 = param7; - packet.command = command; - packet.target_system = target_system; - packet.target_component = target_component; - packet.confirmation = confirmation; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_LONG, (const char *)&packet, MAVLINK_MSG_ID_COMMAND_LONG_MIN_LEN, MAVLINK_MSG_ID_COMMAND_LONG_LEN, MAVLINK_MSG_ID_COMMAND_LONG_CRC); -#endif -} - -/** - * @brief Send a command_long message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_command_long_send_struct(mavlink_channel_t chan, const mavlink_command_long_t* command_long) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_command_long_send(chan, command_long->target_system, command_long->target_component, command_long->command, command_long->confirmation, command_long->param1, command_long->param2, command_long->param3, command_long->param4, command_long->param5, command_long->param6, command_long->param7); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_LONG, (const char *)command_long, MAVLINK_MSG_ID_COMMAND_LONG_MIN_LEN, MAVLINK_MSG_ID_COMMAND_LONG_LEN, MAVLINK_MSG_ID_COMMAND_LONG_CRC); -#endif -} - -#if MAVLINK_MSG_ID_COMMAND_LONG_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_command_long_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t command, uint8_t confirmation, float param1, float param2, float param3, float param4, float param5, float param6, float param7) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_float(buf, 0, param1); - _mav_put_float(buf, 4, param2); - _mav_put_float(buf, 8, param3); - _mav_put_float(buf, 12, param4); - _mav_put_float(buf, 16, param5); - _mav_put_float(buf, 20, param6); - _mav_put_float(buf, 24, param7); - _mav_put_uint16_t(buf, 28, command); - _mav_put_uint8_t(buf, 30, target_system); - _mav_put_uint8_t(buf, 31, target_component); - _mav_put_uint8_t(buf, 32, confirmation); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_LONG, buf, MAVLINK_MSG_ID_COMMAND_LONG_MIN_LEN, MAVLINK_MSG_ID_COMMAND_LONG_LEN, MAVLINK_MSG_ID_COMMAND_LONG_CRC); -#else - mavlink_command_long_t *packet = (mavlink_command_long_t *)msgbuf; - packet->param1 = param1; - packet->param2 = param2; - packet->param3 = param3; - packet->param4 = param4; - packet->param5 = param5; - packet->param6 = param6; - packet->param7 = param7; - packet->command = command; - packet->target_system = target_system; - packet->target_component = target_component; - packet->confirmation = confirmation; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_LONG, (const char *)packet, MAVLINK_MSG_ID_COMMAND_LONG_MIN_LEN, MAVLINK_MSG_ID_COMMAND_LONG_LEN, MAVLINK_MSG_ID_COMMAND_LONG_CRC); -#endif -} -#endif - -#endif - -// MESSAGE COMMAND_LONG UNPACKING - - -/** - * @brief Get field target_system from command_long message - * - * @return System which should execute the command - */ -static inline uint8_t mavlink_msg_command_long_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 30); -} - -/** - * @brief Get field target_component from command_long message - * - * @return Component which should execute the command, 0 for all components - */ -static inline uint8_t mavlink_msg_command_long_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 31); -} - -/** - * @brief Get field command from command_long message - * - * @return Command ID (of command to send). - */ -static inline uint16_t mavlink_msg_command_long_get_command(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 28); -} - -/** - * @brief Get field confirmation from command_long message - * - * @return 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) - */ -static inline uint8_t mavlink_msg_command_long_get_confirmation(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 32); -} - -/** - * @brief Get field param1 from command_long message - * - * @return Parameter 1 (for the specific command). - */ -static inline float mavlink_msg_command_long_get_param1(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 0); -} - -/** - * @brief Get field param2 from command_long message - * - * @return Parameter 2 (for the specific command). - */ -static inline float mavlink_msg_command_long_get_param2(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 4); -} - -/** - * @brief Get field param3 from command_long message - * - * @return Parameter 3 (for the specific command). - */ -static inline float mavlink_msg_command_long_get_param3(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field param4 from command_long message - * - * @return Parameter 4 (for the specific command). - */ -static inline float mavlink_msg_command_long_get_param4(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field param5 from command_long message - * - * @return Parameter 5 (for the specific command). - */ -static inline float mavlink_msg_command_long_get_param5(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field param6 from command_long message - * - * @return Parameter 6 (for the specific command). - */ -static inline float mavlink_msg_command_long_get_param6(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Get field param7 from command_long message - * - * @return Parameter 7 (for the specific command). - */ -static inline float mavlink_msg_command_long_get_param7(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Decode a command_long message into a struct - * - * @param msg The message to decode - * @param command_long C-struct to decode the message contents into - */ -static inline void mavlink_msg_command_long_decode(const mavlink_message_t* msg, mavlink_command_long_t* command_long) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - command_long->param1 = mavlink_msg_command_long_get_param1(msg); - command_long->param2 = mavlink_msg_command_long_get_param2(msg); - command_long->param3 = mavlink_msg_command_long_get_param3(msg); - command_long->param4 = mavlink_msg_command_long_get_param4(msg); - command_long->param5 = mavlink_msg_command_long_get_param5(msg); - command_long->param6 = mavlink_msg_command_long_get_param6(msg); - command_long->param7 = mavlink_msg_command_long_get_param7(msg); - command_long->command = mavlink_msg_command_long_get_command(msg); - command_long->target_system = mavlink_msg_command_long_get_target_system(msg); - command_long->target_component = mavlink_msg_command_long_get_target_component(msg); - command_long->confirmation = mavlink_msg_command_long_get_confirmation(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_COMMAND_LONG_LEN? msg->len : MAVLINK_MSG_ID_COMMAND_LONG_LEN; - memset(command_long, 0, MAVLINK_MSG_ID_COMMAND_LONG_LEN); - memcpy(command_long, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_component_information.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_component_information.h deleted file mode 100644 index 05ef49f2..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_component_information.h +++ /dev/null @@ -1,306 +0,0 @@ -#pragma once -// MESSAGE COMPONENT_INFORMATION PACKING - -#define MAVLINK_MSG_ID_COMPONENT_INFORMATION 395 - - -typedef struct __mavlink_component_information_t { - uint32_t time_boot_ms; /*< [ms] Timestamp (time since system boot).*/ - uint32_t general_metadata_file_crc; /*< CRC32 of the general metadata file (general_metadata_uri).*/ - uint32_t peripherals_metadata_file_crc; /*< CRC32 of peripherals metadata file (peripherals_metadata_uri).*/ - char general_metadata_uri[100]; /*< MAVLink FTP URI for the general metadata file (COMP_METADATA_TYPE_GENERAL), which may be compressed with xz. The file contains general component metadata, and may contain URI links for additional metadata (see COMP_METADATA_TYPE). The information is static from boot, and may be generated at compile time. The string needs to be zero terminated.*/ - char peripherals_metadata_uri[100]; /*< (Optional) MAVLink FTP URI for the peripherals metadata file (COMP_METADATA_TYPE_PERIPHERALS), which may be compressed with xz. This contains data about "attached components" such as UAVCAN nodes. The peripherals are in a separate file because the information must be generated dynamically at runtime. The string needs to be zero terminated.*/ -} mavlink_component_information_t; - -#define MAVLINK_MSG_ID_COMPONENT_INFORMATION_LEN 212 -#define MAVLINK_MSG_ID_COMPONENT_INFORMATION_MIN_LEN 212 -#define MAVLINK_MSG_ID_395_LEN 212 -#define MAVLINK_MSG_ID_395_MIN_LEN 212 - -#define MAVLINK_MSG_ID_COMPONENT_INFORMATION_CRC 0 -#define MAVLINK_MSG_ID_395_CRC 0 - -#define MAVLINK_MSG_COMPONENT_INFORMATION_FIELD_GENERAL_METADATA_URI_LEN 100 -#define MAVLINK_MSG_COMPONENT_INFORMATION_FIELD_PERIPHERALS_METADATA_URI_LEN 100 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_COMPONENT_INFORMATION { \ - 395, \ - "COMPONENT_INFORMATION", \ - 5, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_component_information_t, time_boot_ms) }, \ - { "general_metadata_file_crc", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_component_information_t, general_metadata_file_crc) }, \ - { "general_metadata_uri", NULL, MAVLINK_TYPE_CHAR, 100, 12, offsetof(mavlink_component_information_t, general_metadata_uri) }, \ - { "peripherals_metadata_file_crc", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_component_information_t, peripherals_metadata_file_crc) }, \ - { "peripherals_metadata_uri", NULL, MAVLINK_TYPE_CHAR, 100, 112, offsetof(mavlink_component_information_t, peripherals_metadata_uri) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_COMPONENT_INFORMATION { \ - "COMPONENT_INFORMATION", \ - 5, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_component_information_t, time_boot_ms) }, \ - { "general_metadata_file_crc", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_component_information_t, general_metadata_file_crc) }, \ - { "general_metadata_uri", NULL, MAVLINK_TYPE_CHAR, 100, 12, offsetof(mavlink_component_information_t, general_metadata_uri) }, \ - { "peripherals_metadata_file_crc", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_component_information_t, peripherals_metadata_file_crc) }, \ - { "peripherals_metadata_uri", NULL, MAVLINK_TYPE_CHAR, 100, 112, offsetof(mavlink_component_information_t, peripherals_metadata_uri) }, \ - } \ -} -#endif - -/** - * @brief Pack a component_information message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param time_boot_ms [ms] Timestamp (time since system boot). - * @param general_metadata_file_crc CRC32 of the general metadata file (general_metadata_uri). - * @param general_metadata_uri MAVLink FTP URI for the general metadata file (COMP_METADATA_TYPE_GENERAL), which may be compressed with xz. The file contains general component metadata, and may contain URI links for additional metadata (see COMP_METADATA_TYPE). The information is static from boot, and may be generated at compile time. The string needs to be zero terminated. - * @param peripherals_metadata_file_crc CRC32 of peripherals metadata file (peripherals_metadata_uri). - * @param peripherals_metadata_uri (Optional) MAVLink FTP URI for the peripherals metadata file (COMP_METADATA_TYPE_PERIPHERALS), which may be compressed with xz. This contains data about "attached components" such as UAVCAN nodes. The peripherals are in a separate file because the information must be generated dynamically at runtime. The string needs to be zero terminated. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_component_information_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint32_t time_boot_ms, uint32_t general_metadata_file_crc, const char *general_metadata_uri, uint32_t peripherals_metadata_file_crc, const char *peripherals_metadata_uri) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_COMPONENT_INFORMATION_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_uint32_t(buf, 4, general_metadata_file_crc); - _mav_put_uint32_t(buf, 8, peripherals_metadata_file_crc); - _mav_put_char_array(buf, 12, general_metadata_uri, 100); - _mav_put_char_array(buf, 112, peripherals_metadata_uri, 100); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_COMPONENT_INFORMATION_LEN); -#else - mavlink_component_information_t packet; - packet.time_boot_ms = time_boot_ms; - packet.general_metadata_file_crc = general_metadata_file_crc; - packet.peripherals_metadata_file_crc = peripherals_metadata_file_crc; - mav_array_memcpy(packet.general_metadata_uri, general_metadata_uri, sizeof(char)*100); - mav_array_memcpy(packet.peripherals_metadata_uri, peripherals_metadata_uri, sizeof(char)*100); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_COMPONENT_INFORMATION_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_COMPONENT_INFORMATION; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_COMPONENT_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_COMPONENT_INFORMATION_LEN, MAVLINK_MSG_ID_COMPONENT_INFORMATION_CRC); -} - -/** - * @brief Pack a component_information message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_boot_ms [ms] Timestamp (time since system boot). - * @param general_metadata_file_crc CRC32 of the general metadata file (general_metadata_uri). - * @param general_metadata_uri MAVLink FTP URI for the general metadata file (COMP_METADATA_TYPE_GENERAL), which may be compressed with xz. The file contains general component metadata, and may contain URI links for additional metadata (see COMP_METADATA_TYPE). The information is static from boot, and may be generated at compile time. The string needs to be zero terminated. - * @param peripherals_metadata_file_crc CRC32 of peripherals metadata file (peripherals_metadata_uri). - * @param peripherals_metadata_uri (Optional) MAVLink FTP URI for the peripherals metadata file (COMP_METADATA_TYPE_PERIPHERALS), which may be compressed with xz. This contains data about "attached components" such as UAVCAN nodes. The peripherals are in a separate file because the information must be generated dynamically at runtime. The string needs to be zero terminated. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_component_information_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint32_t time_boot_ms,uint32_t general_metadata_file_crc,const char *general_metadata_uri,uint32_t peripherals_metadata_file_crc,const char *peripherals_metadata_uri) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_COMPONENT_INFORMATION_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_uint32_t(buf, 4, general_metadata_file_crc); - _mav_put_uint32_t(buf, 8, peripherals_metadata_file_crc); - _mav_put_char_array(buf, 12, general_metadata_uri, 100); - _mav_put_char_array(buf, 112, peripherals_metadata_uri, 100); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_COMPONENT_INFORMATION_LEN); -#else - mavlink_component_information_t packet; - packet.time_boot_ms = time_boot_ms; - packet.general_metadata_file_crc = general_metadata_file_crc; - packet.peripherals_metadata_file_crc = peripherals_metadata_file_crc; - mav_array_memcpy(packet.general_metadata_uri, general_metadata_uri, sizeof(char)*100); - mav_array_memcpy(packet.peripherals_metadata_uri, peripherals_metadata_uri, sizeof(char)*100); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_COMPONENT_INFORMATION_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_COMPONENT_INFORMATION; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_COMPONENT_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_COMPONENT_INFORMATION_LEN, MAVLINK_MSG_ID_COMPONENT_INFORMATION_CRC); -} - -/** - * @brief Encode a component_information struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param component_information C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_component_information_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_component_information_t* component_information) -{ - return mavlink_msg_component_information_pack(system_id, component_id, msg, component_information->time_boot_ms, component_information->general_metadata_file_crc, component_information->general_metadata_uri, component_information->peripherals_metadata_file_crc, component_information->peripherals_metadata_uri); -} - -/** - * @brief Encode a component_information struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param component_information C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_component_information_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_component_information_t* component_information) -{ - return mavlink_msg_component_information_pack_chan(system_id, component_id, chan, msg, component_information->time_boot_ms, component_information->general_metadata_file_crc, component_information->general_metadata_uri, component_information->peripherals_metadata_file_crc, component_information->peripherals_metadata_uri); -} - -/** - * @brief Send a component_information message - * @param chan MAVLink channel to send the message - * - * @param time_boot_ms [ms] Timestamp (time since system boot). - * @param general_metadata_file_crc CRC32 of the general metadata file (general_metadata_uri). - * @param general_metadata_uri MAVLink FTP URI for the general metadata file (COMP_METADATA_TYPE_GENERAL), which may be compressed with xz. The file contains general component metadata, and may contain URI links for additional metadata (see COMP_METADATA_TYPE). The information is static from boot, and may be generated at compile time. The string needs to be zero terminated. - * @param peripherals_metadata_file_crc CRC32 of peripherals metadata file (peripherals_metadata_uri). - * @param peripherals_metadata_uri (Optional) MAVLink FTP URI for the peripherals metadata file (COMP_METADATA_TYPE_PERIPHERALS), which may be compressed with xz. This contains data about "attached components" such as UAVCAN nodes. The peripherals are in a separate file because the information must be generated dynamically at runtime. The string needs to be zero terminated. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_component_information_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint32_t general_metadata_file_crc, const char *general_metadata_uri, uint32_t peripherals_metadata_file_crc, const char *peripherals_metadata_uri) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_COMPONENT_INFORMATION_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_uint32_t(buf, 4, general_metadata_file_crc); - _mav_put_uint32_t(buf, 8, peripherals_metadata_file_crc); - _mav_put_char_array(buf, 12, general_metadata_uri, 100); - _mav_put_char_array(buf, 112, peripherals_metadata_uri, 100); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMPONENT_INFORMATION, buf, MAVLINK_MSG_ID_COMPONENT_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_COMPONENT_INFORMATION_LEN, MAVLINK_MSG_ID_COMPONENT_INFORMATION_CRC); -#else - mavlink_component_information_t packet; - packet.time_boot_ms = time_boot_ms; - packet.general_metadata_file_crc = general_metadata_file_crc; - packet.peripherals_metadata_file_crc = peripherals_metadata_file_crc; - mav_array_memcpy(packet.general_metadata_uri, general_metadata_uri, sizeof(char)*100); - mav_array_memcpy(packet.peripherals_metadata_uri, peripherals_metadata_uri, sizeof(char)*100); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMPONENT_INFORMATION, (const char *)&packet, MAVLINK_MSG_ID_COMPONENT_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_COMPONENT_INFORMATION_LEN, MAVLINK_MSG_ID_COMPONENT_INFORMATION_CRC); -#endif -} - -/** - * @brief Send a component_information message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_component_information_send_struct(mavlink_channel_t chan, const mavlink_component_information_t* component_information) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_component_information_send(chan, component_information->time_boot_ms, component_information->general_metadata_file_crc, component_information->general_metadata_uri, component_information->peripherals_metadata_file_crc, component_information->peripherals_metadata_uri); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMPONENT_INFORMATION, (const char *)component_information, MAVLINK_MSG_ID_COMPONENT_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_COMPONENT_INFORMATION_LEN, MAVLINK_MSG_ID_COMPONENT_INFORMATION_CRC); -#endif -} - -#if MAVLINK_MSG_ID_COMPONENT_INFORMATION_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_component_information_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint32_t general_metadata_file_crc, const char *general_metadata_uri, uint32_t peripherals_metadata_file_crc, const char *peripherals_metadata_uri) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_uint32_t(buf, 4, general_metadata_file_crc); - _mav_put_uint32_t(buf, 8, peripherals_metadata_file_crc); - _mav_put_char_array(buf, 12, general_metadata_uri, 100); - _mav_put_char_array(buf, 112, peripherals_metadata_uri, 100); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMPONENT_INFORMATION, buf, MAVLINK_MSG_ID_COMPONENT_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_COMPONENT_INFORMATION_LEN, MAVLINK_MSG_ID_COMPONENT_INFORMATION_CRC); -#else - mavlink_component_information_t *packet = (mavlink_component_information_t *)msgbuf; - packet->time_boot_ms = time_boot_ms; - packet->general_metadata_file_crc = general_metadata_file_crc; - packet->peripherals_metadata_file_crc = peripherals_metadata_file_crc; - mav_array_memcpy(packet->general_metadata_uri, general_metadata_uri, sizeof(char)*100); - mav_array_memcpy(packet->peripherals_metadata_uri, peripherals_metadata_uri, sizeof(char)*100); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMPONENT_INFORMATION, (const char *)packet, MAVLINK_MSG_ID_COMPONENT_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_COMPONENT_INFORMATION_LEN, MAVLINK_MSG_ID_COMPONENT_INFORMATION_CRC); -#endif -} -#endif - -#endif - -// MESSAGE COMPONENT_INFORMATION UNPACKING - - -/** - * @brief Get field time_boot_ms from component_information message - * - * @return [ms] Timestamp (time since system boot). - */ -static inline uint32_t mavlink_msg_component_information_get_time_boot_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field general_metadata_file_crc from component_information message - * - * @return CRC32 of the general metadata file (general_metadata_uri). - */ -static inline uint32_t mavlink_msg_component_information_get_general_metadata_file_crc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 4); -} - -/** - * @brief Get field general_metadata_uri from component_information message - * - * @return MAVLink FTP URI for the general metadata file (COMP_METADATA_TYPE_GENERAL), which may be compressed with xz. The file contains general component metadata, and may contain URI links for additional metadata (see COMP_METADATA_TYPE). The information is static from boot, and may be generated at compile time. The string needs to be zero terminated. - */ -static inline uint16_t mavlink_msg_component_information_get_general_metadata_uri(const mavlink_message_t* msg, char *general_metadata_uri) -{ - return _MAV_RETURN_char_array(msg, general_metadata_uri, 100, 12); -} - -/** - * @brief Get field peripherals_metadata_file_crc from component_information message - * - * @return CRC32 of peripherals metadata file (peripherals_metadata_uri). - */ -static inline uint32_t mavlink_msg_component_information_get_peripherals_metadata_file_crc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 8); -} - -/** - * @brief Get field peripherals_metadata_uri from component_information message - * - * @return (Optional) MAVLink FTP URI for the peripherals metadata file (COMP_METADATA_TYPE_PERIPHERALS), which may be compressed with xz. This contains data about "attached components" such as UAVCAN nodes. The peripherals are in a separate file because the information must be generated dynamically at runtime. The string needs to be zero terminated. - */ -static inline uint16_t mavlink_msg_component_information_get_peripherals_metadata_uri(const mavlink_message_t* msg, char *peripherals_metadata_uri) -{ - return _MAV_RETURN_char_array(msg, peripherals_metadata_uri, 100, 112); -} - -/** - * @brief Decode a component_information message into a struct - * - * @param msg The message to decode - * @param component_information C-struct to decode the message contents into - */ -static inline void mavlink_msg_component_information_decode(const mavlink_message_t* msg, mavlink_component_information_t* component_information) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - component_information->time_boot_ms = mavlink_msg_component_information_get_time_boot_ms(msg); - component_information->general_metadata_file_crc = mavlink_msg_component_information_get_general_metadata_file_crc(msg); - component_information->peripherals_metadata_file_crc = mavlink_msg_component_information_get_peripherals_metadata_file_crc(msg); - mavlink_msg_component_information_get_general_metadata_uri(msg, component_information->general_metadata_uri); - mavlink_msg_component_information_get_peripherals_metadata_uri(msg, component_information->peripherals_metadata_uri); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_COMPONENT_INFORMATION_LEN? msg->len : MAVLINK_MSG_ID_COMPONENT_INFORMATION_LEN; - memset(component_information, 0, MAVLINK_MSG_ID_COMPONENT_INFORMATION_LEN); - memcpy(component_information, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_component_metadata.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_component_metadata.h deleted file mode 100644 index 57afc9ab..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_component_metadata.h +++ /dev/null @@ -1,255 +0,0 @@ -#pragma once -// MESSAGE COMPONENT_METADATA PACKING - -#define MAVLINK_MSG_ID_COMPONENT_METADATA 397 - - -typedef struct __mavlink_component_metadata_t { - uint32_t time_boot_ms; /*< [ms] Timestamp (time since system boot).*/ - uint32_t file_crc; /*< CRC32 of the general metadata file.*/ - char uri[100]; /*< MAVLink FTP URI for the general metadata file (COMP_METADATA_TYPE_GENERAL), which may be compressed with xz. The file contains general component metadata, and may contain URI links for additional metadata (see COMP_METADATA_TYPE). The information is static from boot, and may be generated at compile time. The string needs to be zero terminated.*/ -} mavlink_component_metadata_t; - -#define MAVLINK_MSG_ID_COMPONENT_METADATA_LEN 108 -#define MAVLINK_MSG_ID_COMPONENT_METADATA_MIN_LEN 108 -#define MAVLINK_MSG_ID_397_LEN 108 -#define MAVLINK_MSG_ID_397_MIN_LEN 108 - -#define MAVLINK_MSG_ID_COMPONENT_METADATA_CRC 182 -#define MAVLINK_MSG_ID_397_CRC 182 - -#define MAVLINK_MSG_COMPONENT_METADATA_FIELD_URI_LEN 100 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_COMPONENT_METADATA { \ - 397, \ - "COMPONENT_METADATA", \ - 3, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_component_metadata_t, time_boot_ms) }, \ - { "file_crc", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_component_metadata_t, file_crc) }, \ - { "uri", NULL, MAVLINK_TYPE_CHAR, 100, 8, offsetof(mavlink_component_metadata_t, uri) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_COMPONENT_METADATA { \ - "COMPONENT_METADATA", \ - 3, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_component_metadata_t, time_boot_ms) }, \ - { "file_crc", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_component_metadata_t, file_crc) }, \ - { "uri", NULL, MAVLINK_TYPE_CHAR, 100, 8, offsetof(mavlink_component_metadata_t, uri) }, \ - } \ -} -#endif - -/** - * @brief Pack a component_metadata message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param time_boot_ms [ms] Timestamp (time since system boot). - * @param file_crc CRC32 of the general metadata file. - * @param uri MAVLink FTP URI for the general metadata file (COMP_METADATA_TYPE_GENERAL), which may be compressed with xz. The file contains general component metadata, and may contain URI links for additional metadata (see COMP_METADATA_TYPE). The information is static from boot, and may be generated at compile time. The string needs to be zero terminated. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_component_metadata_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint32_t time_boot_ms, uint32_t file_crc, const char *uri) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_COMPONENT_METADATA_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_uint32_t(buf, 4, file_crc); - _mav_put_char_array(buf, 8, uri, 100); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_COMPONENT_METADATA_LEN); -#else - mavlink_component_metadata_t packet; - packet.time_boot_ms = time_boot_ms; - packet.file_crc = file_crc; - mav_array_memcpy(packet.uri, uri, sizeof(char)*100); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_COMPONENT_METADATA_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_COMPONENT_METADATA; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_COMPONENT_METADATA_MIN_LEN, MAVLINK_MSG_ID_COMPONENT_METADATA_LEN, MAVLINK_MSG_ID_COMPONENT_METADATA_CRC); -} - -/** - * @brief Pack a component_metadata message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_boot_ms [ms] Timestamp (time since system boot). - * @param file_crc CRC32 of the general metadata file. - * @param uri MAVLink FTP URI for the general metadata file (COMP_METADATA_TYPE_GENERAL), which may be compressed with xz. The file contains general component metadata, and may contain URI links for additional metadata (see COMP_METADATA_TYPE). The information is static from boot, and may be generated at compile time. The string needs to be zero terminated. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_component_metadata_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint32_t time_boot_ms,uint32_t file_crc,const char *uri) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_COMPONENT_METADATA_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_uint32_t(buf, 4, file_crc); - _mav_put_char_array(buf, 8, uri, 100); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_COMPONENT_METADATA_LEN); -#else - mavlink_component_metadata_t packet; - packet.time_boot_ms = time_boot_ms; - packet.file_crc = file_crc; - mav_array_memcpy(packet.uri, uri, sizeof(char)*100); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_COMPONENT_METADATA_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_COMPONENT_METADATA; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_COMPONENT_METADATA_MIN_LEN, MAVLINK_MSG_ID_COMPONENT_METADATA_LEN, MAVLINK_MSG_ID_COMPONENT_METADATA_CRC); -} - -/** - * @brief Encode a component_metadata struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param component_metadata C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_component_metadata_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_component_metadata_t* component_metadata) -{ - return mavlink_msg_component_metadata_pack(system_id, component_id, msg, component_metadata->time_boot_ms, component_metadata->file_crc, component_metadata->uri); -} - -/** - * @brief Encode a component_metadata struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param component_metadata C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_component_metadata_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_component_metadata_t* component_metadata) -{ - return mavlink_msg_component_metadata_pack_chan(system_id, component_id, chan, msg, component_metadata->time_boot_ms, component_metadata->file_crc, component_metadata->uri); -} - -/** - * @brief Send a component_metadata message - * @param chan MAVLink channel to send the message - * - * @param time_boot_ms [ms] Timestamp (time since system boot). - * @param file_crc CRC32 of the general metadata file. - * @param uri MAVLink FTP URI for the general metadata file (COMP_METADATA_TYPE_GENERAL), which may be compressed with xz. The file contains general component metadata, and may contain URI links for additional metadata (see COMP_METADATA_TYPE). The information is static from boot, and may be generated at compile time. The string needs to be zero terminated. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_component_metadata_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint32_t file_crc, const char *uri) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_COMPONENT_METADATA_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_uint32_t(buf, 4, file_crc); - _mav_put_char_array(buf, 8, uri, 100); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMPONENT_METADATA, buf, MAVLINK_MSG_ID_COMPONENT_METADATA_MIN_LEN, MAVLINK_MSG_ID_COMPONENT_METADATA_LEN, MAVLINK_MSG_ID_COMPONENT_METADATA_CRC); -#else - mavlink_component_metadata_t packet; - packet.time_boot_ms = time_boot_ms; - packet.file_crc = file_crc; - mav_array_memcpy(packet.uri, uri, sizeof(char)*100); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMPONENT_METADATA, (const char *)&packet, MAVLINK_MSG_ID_COMPONENT_METADATA_MIN_LEN, MAVLINK_MSG_ID_COMPONENT_METADATA_LEN, MAVLINK_MSG_ID_COMPONENT_METADATA_CRC); -#endif -} - -/** - * @brief Send a component_metadata message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_component_metadata_send_struct(mavlink_channel_t chan, const mavlink_component_metadata_t* component_metadata) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_component_metadata_send(chan, component_metadata->time_boot_ms, component_metadata->file_crc, component_metadata->uri); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMPONENT_METADATA, (const char *)component_metadata, MAVLINK_MSG_ID_COMPONENT_METADATA_MIN_LEN, MAVLINK_MSG_ID_COMPONENT_METADATA_LEN, MAVLINK_MSG_ID_COMPONENT_METADATA_CRC); -#endif -} - -#if MAVLINK_MSG_ID_COMPONENT_METADATA_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_component_metadata_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint32_t file_crc, const char *uri) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_uint32_t(buf, 4, file_crc); - _mav_put_char_array(buf, 8, uri, 100); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMPONENT_METADATA, buf, MAVLINK_MSG_ID_COMPONENT_METADATA_MIN_LEN, MAVLINK_MSG_ID_COMPONENT_METADATA_LEN, MAVLINK_MSG_ID_COMPONENT_METADATA_CRC); -#else - mavlink_component_metadata_t *packet = (mavlink_component_metadata_t *)msgbuf; - packet->time_boot_ms = time_boot_ms; - packet->file_crc = file_crc; - mav_array_memcpy(packet->uri, uri, sizeof(char)*100); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMPONENT_METADATA, (const char *)packet, MAVLINK_MSG_ID_COMPONENT_METADATA_MIN_LEN, MAVLINK_MSG_ID_COMPONENT_METADATA_LEN, MAVLINK_MSG_ID_COMPONENT_METADATA_CRC); -#endif -} -#endif - -#endif - -// MESSAGE COMPONENT_METADATA UNPACKING - - -/** - * @brief Get field time_boot_ms from component_metadata message - * - * @return [ms] Timestamp (time since system boot). - */ -static inline uint32_t mavlink_msg_component_metadata_get_time_boot_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field file_crc from component_metadata message - * - * @return CRC32 of the general metadata file. - */ -static inline uint32_t mavlink_msg_component_metadata_get_file_crc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 4); -} - -/** - * @brief Get field uri from component_metadata message - * - * @return MAVLink FTP URI for the general metadata file (COMP_METADATA_TYPE_GENERAL), which may be compressed with xz. The file contains general component metadata, and may contain URI links for additional metadata (see COMP_METADATA_TYPE). The information is static from boot, and may be generated at compile time. The string needs to be zero terminated. - */ -static inline uint16_t mavlink_msg_component_metadata_get_uri(const mavlink_message_t* msg, char *uri) -{ - return _MAV_RETURN_char_array(msg, uri, 100, 8); -} - -/** - * @brief Decode a component_metadata message into a struct - * - * @param msg The message to decode - * @param component_metadata C-struct to decode the message contents into - */ -static inline void mavlink_msg_component_metadata_decode(const mavlink_message_t* msg, mavlink_component_metadata_t* component_metadata) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - component_metadata->time_boot_ms = mavlink_msg_component_metadata_get_time_boot_ms(msg); - component_metadata->file_crc = mavlink_msg_component_metadata_get_file_crc(msg); - mavlink_msg_component_metadata_get_uri(msg, component_metadata->uri); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_COMPONENT_METADATA_LEN? msg->len : MAVLINK_MSG_ID_COMPONENT_METADATA_LEN; - memset(component_metadata, 0, MAVLINK_MSG_ID_COMPONENT_METADATA_LEN); - memcpy(component_metadata, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_control_system_state.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_control_system_state.h deleted file mode 100644 index 2e0d6b7a..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_control_system_state.h +++ /dev/null @@ -1,607 +0,0 @@ -#pragma once -// MESSAGE CONTROL_SYSTEM_STATE PACKING - -#define MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE 146 - - -typedef struct __mavlink_control_system_state_t { - uint64_t time_usec; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/ - float x_acc; /*< [m/s/s] X acceleration in body frame*/ - float y_acc; /*< [m/s/s] Y acceleration in body frame*/ - float z_acc; /*< [m/s/s] Z acceleration in body frame*/ - float x_vel; /*< [m/s] X velocity in body frame*/ - float y_vel; /*< [m/s] Y velocity in body frame*/ - float z_vel; /*< [m/s] Z velocity in body frame*/ - float x_pos; /*< [m] X position in local frame*/ - float y_pos; /*< [m] Y position in local frame*/ - float z_pos; /*< [m] Z position in local frame*/ - float airspeed; /*< [m/s] Airspeed, set to -1 if unknown*/ - float vel_variance[3]; /*< Variance of body velocity estimate*/ - float pos_variance[3]; /*< Variance in local position*/ - float q[4]; /*< The attitude, represented as Quaternion*/ - float roll_rate; /*< [rad/s] Angular rate in roll axis*/ - float pitch_rate; /*< [rad/s] Angular rate in pitch axis*/ - float yaw_rate; /*< [rad/s] Angular rate in yaw axis*/ -} mavlink_control_system_state_t; - -#define MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN 100 -#define MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_MIN_LEN 100 -#define MAVLINK_MSG_ID_146_LEN 100 -#define MAVLINK_MSG_ID_146_MIN_LEN 100 - -#define MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_CRC 103 -#define MAVLINK_MSG_ID_146_CRC 103 - -#define MAVLINK_MSG_CONTROL_SYSTEM_STATE_FIELD_VEL_VARIANCE_LEN 3 -#define MAVLINK_MSG_CONTROL_SYSTEM_STATE_FIELD_POS_VARIANCE_LEN 3 -#define MAVLINK_MSG_CONTROL_SYSTEM_STATE_FIELD_Q_LEN 4 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_CONTROL_SYSTEM_STATE { \ - 146, \ - "CONTROL_SYSTEM_STATE", \ - 17, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_control_system_state_t, time_usec) }, \ - { "x_acc", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_control_system_state_t, x_acc) }, \ - { "y_acc", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_control_system_state_t, y_acc) }, \ - { "z_acc", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_control_system_state_t, z_acc) }, \ - { "x_vel", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_control_system_state_t, x_vel) }, \ - { "y_vel", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_control_system_state_t, y_vel) }, \ - { "z_vel", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_control_system_state_t, z_vel) }, \ - { "x_pos", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_control_system_state_t, x_pos) }, \ - { "y_pos", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_control_system_state_t, y_pos) }, \ - { "z_pos", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_control_system_state_t, z_pos) }, \ - { "airspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_control_system_state_t, airspeed) }, \ - { "vel_variance", NULL, MAVLINK_TYPE_FLOAT, 3, 48, offsetof(mavlink_control_system_state_t, vel_variance) }, \ - { "pos_variance", NULL, MAVLINK_TYPE_FLOAT, 3, 60, offsetof(mavlink_control_system_state_t, pos_variance) }, \ - { "q", NULL, MAVLINK_TYPE_FLOAT, 4, 72, offsetof(mavlink_control_system_state_t, q) }, \ - { "roll_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 88, offsetof(mavlink_control_system_state_t, roll_rate) }, \ - { "pitch_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 92, offsetof(mavlink_control_system_state_t, pitch_rate) }, \ - { "yaw_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 96, offsetof(mavlink_control_system_state_t, yaw_rate) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_CONTROL_SYSTEM_STATE { \ - "CONTROL_SYSTEM_STATE", \ - 17, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_control_system_state_t, time_usec) }, \ - { "x_acc", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_control_system_state_t, x_acc) }, \ - { "y_acc", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_control_system_state_t, y_acc) }, \ - { "z_acc", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_control_system_state_t, z_acc) }, \ - { "x_vel", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_control_system_state_t, x_vel) }, \ - { "y_vel", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_control_system_state_t, y_vel) }, \ - { "z_vel", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_control_system_state_t, z_vel) }, \ - { "x_pos", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_control_system_state_t, x_pos) }, \ - { "y_pos", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_control_system_state_t, y_pos) }, \ - { "z_pos", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_control_system_state_t, z_pos) }, \ - { "airspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_control_system_state_t, airspeed) }, \ - { "vel_variance", NULL, MAVLINK_TYPE_FLOAT, 3, 48, offsetof(mavlink_control_system_state_t, vel_variance) }, \ - { "pos_variance", NULL, MAVLINK_TYPE_FLOAT, 3, 60, offsetof(mavlink_control_system_state_t, pos_variance) }, \ - { "q", NULL, MAVLINK_TYPE_FLOAT, 4, 72, offsetof(mavlink_control_system_state_t, q) }, \ - { "roll_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 88, offsetof(mavlink_control_system_state_t, roll_rate) }, \ - { "pitch_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 92, offsetof(mavlink_control_system_state_t, pitch_rate) }, \ - { "yaw_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 96, offsetof(mavlink_control_system_state_t, yaw_rate) }, \ - } \ -} -#endif - -/** - * @brief Pack a control_system_state message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @param x_acc [m/s/s] X acceleration in body frame - * @param y_acc [m/s/s] Y acceleration in body frame - * @param z_acc [m/s/s] Z acceleration in body frame - * @param x_vel [m/s] X velocity in body frame - * @param y_vel [m/s] Y velocity in body frame - * @param z_vel [m/s] Z velocity in body frame - * @param x_pos [m] X position in local frame - * @param y_pos [m] Y position in local frame - * @param z_pos [m] Z position in local frame - * @param airspeed [m/s] Airspeed, set to -1 if unknown - * @param vel_variance Variance of body velocity estimate - * @param pos_variance Variance in local position - * @param q The attitude, represented as Quaternion - * @param roll_rate [rad/s] Angular rate in roll axis - * @param pitch_rate [rad/s] Angular rate in pitch axis - * @param yaw_rate [rad/s] Angular rate in yaw axis - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_control_system_state_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint64_t time_usec, float x_acc, float y_acc, float z_acc, float x_vel, float y_vel, float z_vel, float x_pos, float y_pos, float z_pos, float airspeed, const float *vel_variance, const float *pos_variance, const float *q, float roll_rate, float pitch_rate, float yaw_rate) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, x_acc); - _mav_put_float(buf, 12, y_acc); - _mav_put_float(buf, 16, z_acc); - _mav_put_float(buf, 20, x_vel); - _mav_put_float(buf, 24, y_vel); - _mav_put_float(buf, 28, z_vel); - _mav_put_float(buf, 32, x_pos); - _mav_put_float(buf, 36, y_pos); - _mav_put_float(buf, 40, z_pos); - _mav_put_float(buf, 44, airspeed); - _mav_put_float(buf, 88, roll_rate); - _mav_put_float(buf, 92, pitch_rate); - _mav_put_float(buf, 96, yaw_rate); - _mav_put_float_array(buf, 48, vel_variance, 3); - _mav_put_float_array(buf, 60, pos_variance, 3); - _mav_put_float_array(buf, 72, q, 4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN); -#else - mavlink_control_system_state_t packet; - packet.time_usec = time_usec; - packet.x_acc = x_acc; - packet.y_acc = y_acc; - packet.z_acc = z_acc; - packet.x_vel = x_vel; - packet.y_vel = y_vel; - packet.z_vel = z_vel; - packet.x_pos = x_pos; - packet.y_pos = y_pos; - packet.z_pos = z_pos; - packet.airspeed = airspeed; - packet.roll_rate = roll_rate; - packet.pitch_rate = pitch_rate; - packet.yaw_rate = yaw_rate; - mav_array_memcpy(packet.vel_variance, vel_variance, sizeof(float)*3); - mav_array_memcpy(packet.pos_variance, pos_variance, sizeof(float)*3); - mav_array_memcpy(packet.q, q, sizeof(float)*4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_MIN_LEN, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_CRC); -} - -/** - * @brief Pack a control_system_state message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @param x_acc [m/s/s] X acceleration in body frame - * @param y_acc [m/s/s] Y acceleration in body frame - * @param z_acc [m/s/s] Z acceleration in body frame - * @param x_vel [m/s] X velocity in body frame - * @param y_vel [m/s] Y velocity in body frame - * @param z_vel [m/s] Z velocity in body frame - * @param x_pos [m] X position in local frame - * @param y_pos [m] Y position in local frame - * @param z_pos [m] Z position in local frame - * @param airspeed [m/s] Airspeed, set to -1 if unknown - * @param vel_variance Variance of body velocity estimate - * @param pos_variance Variance in local position - * @param q The attitude, represented as Quaternion - * @param roll_rate [rad/s] Angular rate in roll axis - * @param pitch_rate [rad/s] Angular rate in pitch axis - * @param yaw_rate [rad/s] Angular rate in yaw axis - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_control_system_state_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint64_t time_usec,float x_acc,float y_acc,float z_acc,float x_vel,float y_vel,float z_vel,float x_pos,float y_pos,float z_pos,float airspeed,const float *vel_variance,const float *pos_variance,const float *q,float roll_rate,float pitch_rate,float yaw_rate) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, x_acc); - _mav_put_float(buf, 12, y_acc); - _mav_put_float(buf, 16, z_acc); - _mav_put_float(buf, 20, x_vel); - _mav_put_float(buf, 24, y_vel); - _mav_put_float(buf, 28, z_vel); - _mav_put_float(buf, 32, x_pos); - _mav_put_float(buf, 36, y_pos); - _mav_put_float(buf, 40, z_pos); - _mav_put_float(buf, 44, airspeed); - _mav_put_float(buf, 88, roll_rate); - _mav_put_float(buf, 92, pitch_rate); - _mav_put_float(buf, 96, yaw_rate); - _mav_put_float_array(buf, 48, vel_variance, 3); - _mav_put_float_array(buf, 60, pos_variance, 3); - _mav_put_float_array(buf, 72, q, 4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN); -#else - mavlink_control_system_state_t packet; - packet.time_usec = time_usec; - packet.x_acc = x_acc; - packet.y_acc = y_acc; - packet.z_acc = z_acc; - packet.x_vel = x_vel; - packet.y_vel = y_vel; - packet.z_vel = z_vel; - packet.x_pos = x_pos; - packet.y_pos = y_pos; - packet.z_pos = z_pos; - packet.airspeed = airspeed; - packet.roll_rate = roll_rate; - packet.pitch_rate = pitch_rate; - packet.yaw_rate = yaw_rate; - mav_array_memcpy(packet.vel_variance, vel_variance, sizeof(float)*3); - mav_array_memcpy(packet.pos_variance, pos_variance, sizeof(float)*3); - mav_array_memcpy(packet.q, q, sizeof(float)*4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_MIN_LEN, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_CRC); -} - -/** - * @brief Encode a control_system_state struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param control_system_state C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_control_system_state_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_control_system_state_t* control_system_state) -{ - return mavlink_msg_control_system_state_pack(system_id, component_id, msg, control_system_state->time_usec, control_system_state->x_acc, control_system_state->y_acc, control_system_state->z_acc, control_system_state->x_vel, control_system_state->y_vel, control_system_state->z_vel, control_system_state->x_pos, control_system_state->y_pos, control_system_state->z_pos, control_system_state->airspeed, control_system_state->vel_variance, control_system_state->pos_variance, control_system_state->q, control_system_state->roll_rate, control_system_state->pitch_rate, control_system_state->yaw_rate); -} - -/** - * @brief Encode a control_system_state struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param control_system_state C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_control_system_state_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_control_system_state_t* control_system_state) -{ - return mavlink_msg_control_system_state_pack_chan(system_id, component_id, chan, msg, control_system_state->time_usec, control_system_state->x_acc, control_system_state->y_acc, control_system_state->z_acc, control_system_state->x_vel, control_system_state->y_vel, control_system_state->z_vel, control_system_state->x_pos, control_system_state->y_pos, control_system_state->z_pos, control_system_state->airspeed, control_system_state->vel_variance, control_system_state->pos_variance, control_system_state->q, control_system_state->roll_rate, control_system_state->pitch_rate, control_system_state->yaw_rate); -} - -/** - * @brief Send a control_system_state message - * @param chan MAVLink channel to send the message - * - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @param x_acc [m/s/s] X acceleration in body frame - * @param y_acc [m/s/s] Y acceleration in body frame - * @param z_acc [m/s/s] Z acceleration in body frame - * @param x_vel [m/s] X velocity in body frame - * @param y_vel [m/s] Y velocity in body frame - * @param z_vel [m/s] Z velocity in body frame - * @param x_pos [m] X position in local frame - * @param y_pos [m] Y position in local frame - * @param z_pos [m] Z position in local frame - * @param airspeed [m/s] Airspeed, set to -1 if unknown - * @param vel_variance Variance of body velocity estimate - * @param pos_variance Variance in local position - * @param q The attitude, represented as Quaternion - * @param roll_rate [rad/s] Angular rate in roll axis - * @param pitch_rate [rad/s] Angular rate in pitch axis - * @param yaw_rate [rad/s] Angular rate in yaw axis - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_control_system_state_send(mavlink_channel_t chan, uint64_t time_usec, float x_acc, float y_acc, float z_acc, float x_vel, float y_vel, float z_vel, float x_pos, float y_pos, float z_pos, float airspeed, const float *vel_variance, const float *pos_variance, const float *q, float roll_rate, float pitch_rate, float yaw_rate) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, x_acc); - _mav_put_float(buf, 12, y_acc); - _mav_put_float(buf, 16, z_acc); - _mav_put_float(buf, 20, x_vel); - _mav_put_float(buf, 24, y_vel); - _mav_put_float(buf, 28, z_vel); - _mav_put_float(buf, 32, x_pos); - _mav_put_float(buf, 36, y_pos); - _mav_put_float(buf, 40, z_pos); - _mav_put_float(buf, 44, airspeed); - _mav_put_float(buf, 88, roll_rate); - _mav_put_float(buf, 92, pitch_rate); - _mav_put_float(buf, 96, yaw_rate); - _mav_put_float_array(buf, 48, vel_variance, 3); - _mav_put_float_array(buf, 60, pos_variance, 3); - _mav_put_float_array(buf, 72, q, 4); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE, buf, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_MIN_LEN, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_CRC); -#else - mavlink_control_system_state_t packet; - packet.time_usec = time_usec; - packet.x_acc = x_acc; - packet.y_acc = y_acc; - packet.z_acc = z_acc; - packet.x_vel = x_vel; - packet.y_vel = y_vel; - packet.z_vel = z_vel; - packet.x_pos = x_pos; - packet.y_pos = y_pos; - packet.z_pos = z_pos; - packet.airspeed = airspeed; - packet.roll_rate = roll_rate; - packet.pitch_rate = pitch_rate; - packet.yaw_rate = yaw_rate; - mav_array_memcpy(packet.vel_variance, vel_variance, sizeof(float)*3); - mav_array_memcpy(packet.pos_variance, pos_variance, sizeof(float)*3); - mav_array_memcpy(packet.q, q, sizeof(float)*4); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE, (const char *)&packet, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_MIN_LEN, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_CRC); -#endif -} - -/** - * @brief Send a control_system_state message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_control_system_state_send_struct(mavlink_channel_t chan, const mavlink_control_system_state_t* control_system_state) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_control_system_state_send(chan, control_system_state->time_usec, control_system_state->x_acc, control_system_state->y_acc, control_system_state->z_acc, control_system_state->x_vel, control_system_state->y_vel, control_system_state->z_vel, control_system_state->x_pos, control_system_state->y_pos, control_system_state->z_pos, control_system_state->airspeed, control_system_state->vel_variance, control_system_state->pos_variance, control_system_state->q, control_system_state->roll_rate, control_system_state->pitch_rate, control_system_state->yaw_rate); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE, (const char *)control_system_state, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_MIN_LEN, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_CRC); -#endif -} - -#if MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_control_system_state_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, float x_acc, float y_acc, float z_acc, float x_vel, float y_vel, float z_vel, float x_pos, float y_pos, float z_pos, float airspeed, const float *vel_variance, const float *pos_variance, const float *q, float roll_rate, float pitch_rate, float yaw_rate) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, x_acc); - _mav_put_float(buf, 12, y_acc); - _mav_put_float(buf, 16, z_acc); - _mav_put_float(buf, 20, x_vel); - _mav_put_float(buf, 24, y_vel); - _mav_put_float(buf, 28, z_vel); - _mav_put_float(buf, 32, x_pos); - _mav_put_float(buf, 36, y_pos); - _mav_put_float(buf, 40, z_pos); - _mav_put_float(buf, 44, airspeed); - _mav_put_float(buf, 88, roll_rate); - _mav_put_float(buf, 92, pitch_rate); - _mav_put_float(buf, 96, yaw_rate); - _mav_put_float_array(buf, 48, vel_variance, 3); - _mav_put_float_array(buf, 60, pos_variance, 3); - _mav_put_float_array(buf, 72, q, 4); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE, buf, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_MIN_LEN, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_CRC); -#else - mavlink_control_system_state_t *packet = (mavlink_control_system_state_t *)msgbuf; - packet->time_usec = time_usec; - packet->x_acc = x_acc; - packet->y_acc = y_acc; - packet->z_acc = z_acc; - packet->x_vel = x_vel; - packet->y_vel = y_vel; - packet->z_vel = z_vel; - packet->x_pos = x_pos; - packet->y_pos = y_pos; - packet->z_pos = z_pos; - packet->airspeed = airspeed; - packet->roll_rate = roll_rate; - packet->pitch_rate = pitch_rate; - packet->yaw_rate = yaw_rate; - mav_array_memcpy(packet->vel_variance, vel_variance, sizeof(float)*3); - mav_array_memcpy(packet->pos_variance, pos_variance, sizeof(float)*3); - mav_array_memcpy(packet->q, q, sizeof(float)*4); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE, (const char *)packet, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_MIN_LEN, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_CRC); -#endif -} -#endif - -#endif - -// MESSAGE CONTROL_SYSTEM_STATE UNPACKING - - -/** - * @brief Get field time_usec from control_system_state message - * - * @return [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - */ -static inline uint64_t mavlink_msg_control_system_state_get_time_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field x_acc from control_system_state message - * - * @return [m/s/s] X acceleration in body frame - */ -static inline float mavlink_msg_control_system_state_get_x_acc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field y_acc from control_system_state message - * - * @return [m/s/s] Y acceleration in body frame - */ -static inline float mavlink_msg_control_system_state_get_y_acc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field z_acc from control_system_state message - * - * @return [m/s/s] Z acceleration in body frame - */ -static inline float mavlink_msg_control_system_state_get_z_acc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field x_vel from control_system_state message - * - * @return [m/s] X velocity in body frame - */ -static inline float mavlink_msg_control_system_state_get_x_vel(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Get field y_vel from control_system_state message - * - * @return [m/s] Y velocity in body frame - */ -static inline float mavlink_msg_control_system_state_get_y_vel(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Get field z_vel from control_system_state message - * - * @return [m/s] Z velocity in body frame - */ -static inline float mavlink_msg_control_system_state_get_z_vel(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 28); -} - -/** - * @brief Get field x_pos from control_system_state message - * - * @return [m] X position in local frame - */ -static inline float mavlink_msg_control_system_state_get_x_pos(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 32); -} - -/** - * @brief Get field y_pos from control_system_state message - * - * @return [m] Y position in local frame - */ -static inline float mavlink_msg_control_system_state_get_y_pos(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 36); -} - -/** - * @brief Get field z_pos from control_system_state message - * - * @return [m] Z position in local frame - */ -static inline float mavlink_msg_control_system_state_get_z_pos(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 40); -} - -/** - * @brief Get field airspeed from control_system_state message - * - * @return [m/s] Airspeed, set to -1 if unknown - */ -static inline float mavlink_msg_control_system_state_get_airspeed(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 44); -} - -/** - * @brief Get field vel_variance from control_system_state message - * - * @return Variance of body velocity estimate - */ -static inline uint16_t mavlink_msg_control_system_state_get_vel_variance(const mavlink_message_t* msg, float *vel_variance) -{ - return _MAV_RETURN_float_array(msg, vel_variance, 3, 48); -} - -/** - * @brief Get field pos_variance from control_system_state message - * - * @return Variance in local position - */ -static inline uint16_t mavlink_msg_control_system_state_get_pos_variance(const mavlink_message_t* msg, float *pos_variance) -{ - return _MAV_RETURN_float_array(msg, pos_variance, 3, 60); -} - -/** - * @brief Get field q from control_system_state message - * - * @return The attitude, represented as Quaternion - */ -static inline uint16_t mavlink_msg_control_system_state_get_q(const mavlink_message_t* msg, float *q) -{ - return _MAV_RETURN_float_array(msg, q, 4, 72); -} - -/** - * @brief Get field roll_rate from control_system_state message - * - * @return [rad/s] Angular rate in roll axis - */ -static inline float mavlink_msg_control_system_state_get_roll_rate(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 88); -} - -/** - * @brief Get field pitch_rate from control_system_state message - * - * @return [rad/s] Angular rate in pitch axis - */ -static inline float mavlink_msg_control_system_state_get_pitch_rate(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 92); -} - -/** - * @brief Get field yaw_rate from control_system_state message - * - * @return [rad/s] Angular rate in yaw axis - */ -static inline float mavlink_msg_control_system_state_get_yaw_rate(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 96); -} - -/** - * @brief Decode a control_system_state message into a struct - * - * @param msg The message to decode - * @param control_system_state C-struct to decode the message contents into - */ -static inline void mavlink_msg_control_system_state_decode(const mavlink_message_t* msg, mavlink_control_system_state_t* control_system_state) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - control_system_state->time_usec = mavlink_msg_control_system_state_get_time_usec(msg); - control_system_state->x_acc = mavlink_msg_control_system_state_get_x_acc(msg); - control_system_state->y_acc = mavlink_msg_control_system_state_get_y_acc(msg); - control_system_state->z_acc = mavlink_msg_control_system_state_get_z_acc(msg); - control_system_state->x_vel = mavlink_msg_control_system_state_get_x_vel(msg); - control_system_state->y_vel = mavlink_msg_control_system_state_get_y_vel(msg); - control_system_state->z_vel = mavlink_msg_control_system_state_get_z_vel(msg); - control_system_state->x_pos = mavlink_msg_control_system_state_get_x_pos(msg); - control_system_state->y_pos = mavlink_msg_control_system_state_get_y_pos(msg); - control_system_state->z_pos = mavlink_msg_control_system_state_get_z_pos(msg); - control_system_state->airspeed = mavlink_msg_control_system_state_get_airspeed(msg); - mavlink_msg_control_system_state_get_vel_variance(msg, control_system_state->vel_variance); - mavlink_msg_control_system_state_get_pos_variance(msg, control_system_state->pos_variance); - mavlink_msg_control_system_state_get_q(msg, control_system_state->q); - control_system_state->roll_rate = mavlink_msg_control_system_state_get_roll_rate(msg); - control_system_state->pitch_rate = mavlink_msg_control_system_state_get_pitch_rate(msg); - control_system_state->yaw_rate = mavlink_msg_control_system_state_get_yaw_rate(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN? msg->len : MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN; - memset(control_system_state, 0, MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_LEN); - memcpy(control_system_state, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_current_event_sequence.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_current_event_sequence.h deleted file mode 100644 index 0c1ee1f4..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_current_event_sequence.h +++ /dev/null @@ -1,238 +0,0 @@ -#pragma once -// MESSAGE CURRENT_EVENT_SEQUENCE PACKING - -#define MAVLINK_MSG_ID_CURRENT_EVENT_SEQUENCE 411 - - -typedef struct __mavlink_current_event_sequence_t { - uint16_t sequence; /*< Sequence number.*/ - uint8_t flags; /*< Flag bitset.*/ -} mavlink_current_event_sequence_t; - -#define MAVLINK_MSG_ID_CURRENT_EVENT_SEQUENCE_LEN 3 -#define MAVLINK_MSG_ID_CURRENT_EVENT_SEQUENCE_MIN_LEN 3 -#define MAVLINK_MSG_ID_411_LEN 3 -#define MAVLINK_MSG_ID_411_MIN_LEN 3 - -#define MAVLINK_MSG_ID_CURRENT_EVENT_SEQUENCE_CRC 106 -#define MAVLINK_MSG_ID_411_CRC 106 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_CURRENT_EVENT_SEQUENCE { \ - 411, \ - "CURRENT_EVENT_SEQUENCE", \ - 2, \ - { { "sequence", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_current_event_sequence_t, sequence) }, \ - { "flags", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_current_event_sequence_t, flags) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_CURRENT_EVENT_SEQUENCE { \ - "CURRENT_EVENT_SEQUENCE", \ - 2, \ - { { "sequence", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_current_event_sequence_t, sequence) }, \ - { "flags", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_current_event_sequence_t, flags) }, \ - } \ -} -#endif - -/** - * @brief Pack a current_event_sequence message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param sequence Sequence number. - * @param flags Flag bitset. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_current_event_sequence_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint16_t sequence, uint8_t flags) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_CURRENT_EVENT_SEQUENCE_LEN]; - _mav_put_uint16_t(buf, 0, sequence); - _mav_put_uint8_t(buf, 2, flags); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CURRENT_EVENT_SEQUENCE_LEN); -#else - mavlink_current_event_sequence_t packet; - packet.sequence = sequence; - packet.flags = flags; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CURRENT_EVENT_SEQUENCE_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_CURRENT_EVENT_SEQUENCE; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_CURRENT_EVENT_SEQUENCE_MIN_LEN, MAVLINK_MSG_ID_CURRENT_EVENT_SEQUENCE_LEN, MAVLINK_MSG_ID_CURRENT_EVENT_SEQUENCE_CRC); -} - -/** - * @brief Pack a current_event_sequence message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param sequence Sequence number. - * @param flags Flag bitset. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_current_event_sequence_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint16_t sequence,uint8_t flags) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_CURRENT_EVENT_SEQUENCE_LEN]; - _mav_put_uint16_t(buf, 0, sequence); - _mav_put_uint8_t(buf, 2, flags); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CURRENT_EVENT_SEQUENCE_LEN); -#else - mavlink_current_event_sequence_t packet; - packet.sequence = sequence; - packet.flags = flags; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CURRENT_EVENT_SEQUENCE_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_CURRENT_EVENT_SEQUENCE; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_CURRENT_EVENT_SEQUENCE_MIN_LEN, MAVLINK_MSG_ID_CURRENT_EVENT_SEQUENCE_LEN, MAVLINK_MSG_ID_CURRENT_EVENT_SEQUENCE_CRC); -} - -/** - * @brief Encode a current_event_sequence struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param current_event_sequence C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_current_event_sequence_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_current_event_sequence_t* current_event_sequence) -{ - return mavlink_msg_current_event_sequence_pack(system_id, component_id, msg, current_event_sequence->sequence, current_event_sequence->flags); -} - -/** - * @brief Encode a current_event_sequence struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param current_event_sequence C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_current_event_sequence_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_current_event_sequence_t* current_event_sequence) -{ - return mavlink_msg_current_event_sequence_pack_chan(system_id, component_id, chan, msg, current_event_sequence->sequence, current_event_sequence->flags); -} - -/** - * @brief Send a current_event_sequence message - * @param chan MAVLink channel to send the message - * - * @param sequence Sequence number. - * @param flags Flag bitset. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_current_event_sequence_send(mavlink_channel_t chan, uint16_t sequence, uint8_t flags) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_CURRENT_EVENT_SEQUENCE_LEN]; - _mav_put_uint16_t(buf, 0, sequence); - _mav_put_uint8_t(buf, 2, flags); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CURRENT_EVENT_SEQUENCE, buf, MAVLINK_MSG_ID_CURRENT_EVENT_SEQUENCE_MIN_LEN, MAVLINK_MSG_ID_CURRENT_EVENT_SEQUENCE_LEN, MAVLINK_MSG_ID_CURRENT_EVENT_SEQUENCE_CRC); -#else - mavlink_current_event_sequence_t packet; - packet.sequence = sequence; - packet.flags = flags; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CURRENT_EVENT_SEQUENCE, (const char *)&packet, MAVLINK_MSG_ID_CURRENT_EVENT_SEQUENCE_MIN_LEN, MAVLINK_MSG_ID_CURRENT_EVENT_SEQUENCE_LEN, MAVLINK_MSG_ID_CURRENT_EVENT_SEQUENCE_CRC); -#endif -} - -/** - * @brief Send a current_event_sequence message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_current_event_sequence_send_struct(mavlink_channel_t chan, const mavlink_current_event_sequence_t* current_event_sequence) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_current_event_sequence_send(chan, current_event_sequence->sequence, current_event_sequence->flags); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CURRENT_EVENT_SEQUENCE, (const char *)current_event_sequence, MAVLINK_MSG_ID_CURRENT_EVENT_SEQUENCE_MIN_LEN, MAVLINK_MSG_ID_CURRENT_EVENT_SEQUENCE_LEN, MAVLINK_MSG_ID_CURRENT_EVENT_SEQUENCE_CRC); -#endif -} - -#if MAVLINK_MSG_ID_CURRENT_EVENT_SEQUENCE_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_current_event_sequence_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint16_t sequence, uint8_t flags) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint16_t(buf, 0, sequence); - _mav_put_uint8_t(buf, 2, flags); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CURRENT_EVENT_SEQUENCE, buf, MAVLINK_MSG_ID_CURRENT_EVENT_SEQUENCE_MIN_LEN, MAVLINK_MSG_ID_CURRENT_EVENT_SEQUENCE_LEN, MAVLINK_MSG_ID_CURRENT_EVENT_SEQUENCE_CRC); -#else - mavlink_current_event_sequence_t *packet = (mavlink_current_event_sequence_t *)msgbuf; - packet->sequence = sequence; - packet->flags = flags; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CURRENT_EVENT_SEQUENCE, (const char *)packet, MAVLINK_MSG_ID_CURRENT_EVENT_SEQUENCE_MIN_LEN, MAVLINK_MSG_ID_CURRENT_EVENT_SEQUENCE_LEN, MAVLINK_MSG_ID_CURRENT_EVENT_SEQUENCE_CRC); -#endif -} -#endif - -#endif - -// MESSAGE CURRENT_EVENT_SEQUENCE UNPACKING - - -/** - * @brief Get field sequence from current_event_sequence message - * - * @return Sequence number. - */ -static inline uint16_t mavlink_msg_current_event_sequence_get_sequence(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 0); -} - -/** - * @brief Get field flags from current_event_sequence message - * - * @return Flag bitset. - */ -static inline uint8_t mavlink_msg_current_event_sequence_get_flags(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 2); -} - -/** - * @brief Decode a current_event_sequence message into a struct - * - * @param msg The message to decode - * @param current_event_sequence C-struct to decode the message contents into - */ -static inline void mavlink_msg_current_event_sequence_decode(const mavlink_message_t* msg, mavlink_current_event_sequence_t* current_event_sequence) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - current_event_sequence->sequence = mavlink_msg_current_event_sequence_get_sequence(msg); - current_event_sequence->flags = mavlink_msg_current_event_sequence_get_flags(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_CURRENT_EVENT_SEQUENCE_LEN? msg->len : MAVLINK_MSG_ID_CURRENT_EVENT_SEQUENCE_LEN; - memset(current_event_sequence, 0, MAVLINK_MSG_ID_CURRENT_EVENT_SEQUENCE_LEN); - memcpy(current_event_sequence, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_data_stream.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_data_stream.h deleted file mode 100644 index b8cd6985..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_data_stream.h +++ /dev/null @@ -1,263 +0,0 @@ -#pragma once -// MESSAGE DATA_STREAM PACKING - -#define MAVLINK_MSG_ID_DATA_STREAM 67 - - -typedef struct __mavlink_data_stream_t { - uint16_t message_rate; /*< [Hz] The message rate*/ - uint8_t stream_id; /*< The ID of the requested data stream*/ - uint8_t on_off; /*< 1 stream is enabled, 0 stream is stopped.*/ -} mavlink_data_stream_t; - -#define MAVLINK_MSG_ID_DATA_STREAM_LEN 4 -#define MAVLINK_MSG_ID_DATA_STREAM_MIN_LEN 4 -#define MAVLINK_MSG_ID_67_LEN 4 -#define MAVLINK_MSG_ID_67_MIN_LEN 4 - -#define MAVLINK_MSG_ID_DATA_STREAM_CRC 21 -#define MAVLINK_MSG_ID_67_CRC 21 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_DATA_STREAM { \ - 67, \ - "DATA_STREAM", \ - 3, \ - { { "stream_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_data_stream_t, stream_id) }, \ - { "message_rate", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_data_stream_t, message_rate) }, \ - { "on_off", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_data_stream_t, on_off) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_DATA_STREAM { \ - "DATA_STREAM", \ - 3, \ - { { "stream_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_data_stream_t, stream_id) }, \ - { "message_rate", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_data_stream_t, message_rate) }, \ - { "on_off", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_data_stream_t, on_off) }, \ - } \ -} -#endif - -/** - * @brief Pack a data_stream message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param stream_id The ID of the requested data stream - * @param message_rate [Hz] The message rate - * @param on_off 1 stream is enabled, 0 stream is stopped. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_data_stream_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t stream_id, uint16_t message_rate, uint8_t on_off) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_DATA_STREAM_LEN]; - _mav_put_uint16_t(buf, 0, message_rate); - _mav_put_uint8_t(buf, 2, stream_id); - _mav_put_uint8_t(buf, 3, on_off); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DATA_STREAM_LEN); -#else - mavlink_data_stream_t packet; - packet.message_rate = message_rate; - packet.stream_id = stream_id; - packet.on_off = on_off; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DATA_STREAM_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_DATA_STREAM; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DATA_STREAM_MIN_LEN, MAVLINK_MSG_ID_DATA_STREAM_LEN, MAVLINK_MSG_ID_DATA_STREAM_CRC); -} - -/** - * @brief Pack a data_stream message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param stream_id The ID of the requested data stream - * @param message_rate [Hz] The message rate - * @param on_off 1 stream is enabled, 0 stream is stopped. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_data_stream_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t stream_id,uint16_t message_rate,uint8_t on_off) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_DATA_STREAM_LEN]; - _mav_put_uint16_t(buf, 0, message_rate); - _mav_put_uint8_t(buf, 2, stream_id); - _mav_put_uint8_t(buf, 3, on_off); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DATA_STREAM_LEN); -#else - mavlink_data_stream_t packet; - packet.message_rate = message_rate; - packet.stream_id = stream_id; - packet.on_off = on_off; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DATA_STREAM_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_DATA_STREAM; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DATA_STREAM_MIN_LEN, MAVLINK_MSG_ID_DATA_STREAM_LEN, MAVLINK_MSG_ID_DATA_STREAM_CRC); -} - -/** - * @brief Encode a data_stream struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param data_stream C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_data_stream_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_data_stream_t* data_stream) -{ - return mavlink_msg_data_stream_pack(system_id, component_id, msg, data_stream->stream_id, data_stream->message_rate, data_stream->on_off); -} - -/** - * @brief Encode a data_stream struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param data_stream C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_data_stream_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_data_stream_t* data_stream) -{ - return mavlink_msg_data_stream_pack_chan(system_id, component_id, chan, msg, data_stream->stream_id, data_stream->message_rate, data_stream->on_off); -} - -/** - * @brief Send a data_stream message - * @param chan MAVLink channel to send the message - * - * @param stream_id The ID of the requested data stream - * @param message_rate [Hz] The message rate - * @param on_off 1 stream is enabled, 0 stream is stopped. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_data_stream_send(mavlink_channel_t chan, uint8_t stream_id, uint16_t message_rate, uint8_t on_off) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_DATA_STREAM_LEN]; - _mav_put_uint16_t(buf, 0, message_rate); - _mav_put_uint8_t(buf, 2, stream_id); - _mav_put_uint8_t(buf, 3, on_off); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_STREAM, buf, MAVLINK_MSG_ID_DATA_STREAM_MIN_LEN, MAVLINK_MSG_ID_DATA_STREAM_LEN, MAVLINK_MSG_ID_DATA_STREAM_CRC); -#else - mavlink_data_stream_t packet; - packet.message_rate = message_rate; - packet.stream_id = stream_id; - packet.on_off = on_off; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_STREAM, (const char *)&packet, MAVLINK_MSG_ID_DATA_STREAM_MIN_LEN, MAVLINK_MSG_ID_DATA_STREAM_LEN, MAVLINK_MSG_ID_DATA_STREAM_CRC); -#endif -} - -/** - * @brief Send a data_stream message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_data_stream_send_struct(mavlink_channel_t chan, const mavlink_data_stream_t* data_stream) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_data_stream_send(chan, data_stream->stream_id, data_stream->message_rate, data_stream->on_off); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_STREAM, (const char *)data_stream, MAVLINK_MSG_ID_DATA_STREAM_MIN_LEN, MAVLINK_MSG_ID_DATA_STREAM_LEN, MAVLINK_MSG_ID_DATA_STREAM_CRC); -#endif -} - -#if MAVLINK_MSG_ID_DATA_STREAM_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_data_stream_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t stream_id, uint16_t message_rate, uint8_t on_off) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint16_t(buf, 0, message_rate); - _mav_put_uint8_t(buf, 2, stream_id); - _mav_put_uint8_t(buf, 3, on_off); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_STREAM, buf, MAVLINK_MSG_ID_DATA_STREAM_MIN_LEN, MAVLINK_MSG_ID_DATA_STREAM_LEN, MAVLINK_MSG_ID_DATA_STREAM_CRC); -#else - mavlink_data_stream_t *packet = (mavlink_data_stream_t *)msgbuf; - packet->message_rate = message_rate; - packet->stream_id = stream_id; - packet->on_off = on_off; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_STREAM, (const char *)packet, MAVLINK_MSG_ID_DATA_STREAM_MIN_LEN, MAVLINK_MSG_ID_DATA_STREAM_LEN, MAVLINK_MSG_ID_DATA_STREAM_CRC); -#endif -} -#endif - -#endif - -// MESSAGE DATA_STREAM UNPACKING - - -/** - * @brief Get field stream_id from data_stream message - * - * @return The ID of the requested data stream - */ -static inline uint8_t mavlink_msg_data_stream_get_stream_id(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 2); -} - -/** - * @brief Get field message_rate from data_stream message - * - * @return [Hz] The message rate - */ -static inline uint16_t mavlink_msg_data_stream_get_message_rate(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 0); -} - -/** - * @brief Get field on_off from data_stream message - * - * @return 1 stream is enabled, 0 stream is stopped. - */ -static inline uint8_t mavlink_msg_data_stream_get_on_off(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 3); -} - -/** - * @brief Decode a data_stream message into a struct - * - * @param msg The message to decode - * @param data_stream C-struct to decode the message contents into - */ -static inline void mavlink_msg_data_stream_decode(const mavlink_message_t* msg, mavlink_data_stream_t* data_stream) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - data_stream->message_rate = mavlink_msg_data_stream_get_message_rate(msg); - data_stream->stream_id = mavlink_msg_data_stream_get_stream_id(msg); - data_stream->on_off = mavlink_msg_data_stream_get_on_off(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_DATA_STREAM_LEN? msg->len : MAVLINK_MSG_ID_DATA_STREAM_LEN; - memset(data_stream, 0, MAVLINK_MSG_ID_DATA_STREAM_LEN); - memcpy(data_stream, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_data_transmission_handshake.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_data_transmission_handshake.h deleted file mode 100644 index f6a383c1..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_data_transmission_handshake.h +++ /dev/null @@ -1,363 +0,0 @@ -#pragma once -// MESSAGE DATA_TRANSMISSION_HANDSHAKE PACKING - -#define MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE 130 - - -typedef struct __mavlink_data_transmission_handshake_t { - uint32_t size; /*< [bytes] total data size (set on ACK only).*/ - uint16_t width; /*< Width of a matrix or image.*/ - uint16_t height; /*< Height of a matrix or image.*/ - uint16_t packets; /*< Number of packets being sent (set on ACK only).*/ - uint8_t type; /*< Type of requested/acknowledged data.*/ - uint8_t payload; /*< [bytes] Payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only).*/ - uint8_t jpg_quality; /*< [%] JPEG quality. Values: [1-100].*/ -} mavlink_data_transmission_handshake_t; - -#define MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN 13 -#define MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_MIN_LEN 13 -#define MAVLINK_MSG_ID_130_LEN 13 -#define MAVLINK_MSG_ID_130_MIN_LEN 13 - -#define MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_CRC 29 -#define MAVLINK_MSG_ID_130_CRC 29 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_DATA_TRANSMISSION_HANDSHAKE { \ - 130, \ - "DATA_TRANSMISSION_HANDSHAKE", \ - 7, \ - { { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_data_transmission_handshake_t, type) }, \ - { "size", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_data_transmission_handshake_t, size) }, \ - { "width", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_data_transmission_handshake_t, width) }, \ - { "height", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_data_transmission_handshake_t, height) }, \ - { "packets", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_data_transmission_handshake_t, packets) }, \ - { "payload", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_data_transmission_handshake_t, payload) }, \ - { "jpg_quality", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_data_transmission_handshake_t, jpg_quality) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_DATA_TRANSMISSION_HANDSHAKE { \ - "DATA_TRANSMISSION_HANDSHAKE", \ - 7, \ - { { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_data_transmission_handshake_t, type) }, \ - { "size", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_data_transmission_handshake_t, size) }, \ - { "width", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_data_transmission_handshake_t, width) }, \ - { "height", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_data_transmission_handshake_t, height) }, \ - { "packets", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_data_transmission_handshake_t, packets) }, \ - { "payload", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_data_transmission_handshake_t, payload) }, \ - { "jpg_quality", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_data_transmission_handshake_t, jpg_quality) }, \ - } \ -} -#endif - -/** - * @brief Pack a data_transmission_handshake message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param type Type of requested/acknowledged data. - * @param size [bytes] total data size (set on ACK only). - * @param width Width of a matrix or image. - * @param height Height of a matrix or image. - * @param packets Number of packets being sent (set on ACK only). - * @param payload [bytes] Payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only). - * @param jpg_quality [%] JPEG quality. Values: [1-100]. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_data_transmission_handshake_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t type, uint32_t size, uint16_t width, uint16_t height, uint16_t packets, uint8_t payload, uint8_t jpg_quality) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN]; - _mav_put_uint32_t(buf, 0, size); - _mav_put_uint16_t(buf, 4, width); - _mav_put_uint16_t(buf, 6, height); - _mav_put_uint16_t(buf, 8, packets); - _mav_put_uint8_t(buf, 10, type); - _mav_put_uint8_t(buf, 11, payload); - _mav_put_uint8_t(buf, 12, jpg_quality); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN); -#else - mavlink_data_transmission_handshake_t packet; - packet.size = size; - packet.width = width; - packet.height = height; - packet.packets = packets; - packet.type = type; - packet.payload = payload; - packet.jpg_quality = jpg_quality; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_MIN_LEN, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_CRC); -} - -/** - * @brief Pack a data_transmission_handshake message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param type Type of requested/acknowledged data. - * @param size [bytes] total data size (set on ACK only). - * @param width Width of a matrix or image. - * @param height Height of a matrix or image. - * @param packets Number of packets being sent (set on ACK only). - * @param payload [bytes] Payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only). - * @param jpg_quality [%] JPEG quality. Values: [1-100]. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_data_transmission_handshake_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t type,uint32_t size,uint16_t width,uint16_t height,uint16_t packets,uint8_t payload,uint8_t jpg_quality) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN]; - _mav_put_uint32_t(buf, 0, size); - _mav_put_uint16_t(buf, 4, width); - _mav_put_uint16_t(buf, 6, height); - _mav_put_uint16_t(buf, 8, packets); - _mav_put_uint8_t(buf, 10, type); - _mav_put_uint8_t(buf, 11, payload); - _mav_put_uint8_t(buf, 12, jpg_quality); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN); -#else - mavlink_data_transmission_handshake_t packet; - packet.size = size; - packet.width = width; - packet.height = height; - packet.packets = packets; - packet.type = type; - packet.payload = payload; - packet.jpg_quality = jpg_quality; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_MIN_LEN, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_CRC); -} - -/** - * @brief Encode a data_transmission_handshake struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param data_transmission_handshake C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_data_transmission_handshake_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_data_transmission_handshake_t* data_transmission_handshake) -{ - return mavlink_msg_data_transmission_handshake_pack(system_id, component_id, msg, data_transmission_handshake->type, data_transmission_handshake->size, data_transmission_handshake->width, data_transmission_handshake->height, data_transmission_handshake->packets, data_transmission_handshake->payload, data_transmission_handshake->jpg_quality); -} - -/** - * @brief Encode a data_transmission_handshake struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param data_transmission_handshake C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_data_transmission_handshake_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_data_transmission_handshake_t* data_transmission_handshake) -{ - return mavlink_msg_data_transmission_handshake_pack_chan(system_id, component_id, chan, msg, data_transmission_handshake->type, data_transmission_handshake->size, data_transmission_handshake->width, data_transmission_handshake->height, data_transmission_handshake->packets, data_transmission_handshake->payload, data_transmission_handshake->jpg_quality); -} - -/** - * @brief Send a data_transmission_handshake message - * @param chan MAVLink channel to send the message - * - * @param type Type of requested/acknowledged data. - * @param size [bytes] total data size (set on ACK only). - * @param width Width of a matrix or image. - * @param height Height of a matrix or image. - * @param packets Number of packets being sent (set on ACK only). - * @param payload [bytes] Payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only). - * @param jpg_quality [%] JPEG quality. Values: [1-100]. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_data_transmission_handshake_send(mavlink_channel_t chan, uint8_t type, uint32_t size, uint16_t width, uint16_t height, uint16_t packets, uint8_t payload, uint8_t jpg_quality) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN]; - _mav_put_uint32_t(buf, 0, size); - _mav_put_uint16_t(buf, 4, width); - _mav_put_uint16_t(buf, 6, height); - _mav_put_uint16_t(buf, 8, packets); - _mav_put_uint8_t(buf, 10, type); - _mav_put_uint8_t(buf, 11, payload); - _mav_put_uint8_t(buf, 12, jpg_quality); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE, buf, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_MIN_LEN, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_CRC); -#else - mavlink_data_transmission_handshake_t packet; - packet.size = size; - packet.width = width; - packet.height = height; - packet.packets = packets; - packet.type = type; - packet.payload = payload; - packet.jpg_quality = jpg_quality; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE, (const char *)&packet, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_MIN_LEN, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_CRC); -#endif -} - -/** - * @brief Send a data_transmission_handshake message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_data_transmission_handshake_send_struct(mavlink_channel_t chan, const mavlink_data_transmission_handshake_t* data_transmission_handshake) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_data_transmission_handshake_send(chan, data_transmission_handshake->type, data_transmission_handshake->size, data_transmission_handshake->width, data_transmission_handshake->height, data_transmission_handshake->packets, data_transmission_handshake->payload, data_transmission_handshake->jpg_quality); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE, (const char *)data_transmission_handshake, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_MIN_LEN, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_CRC); -#endif -} - -#if MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_data_transmission_handshake_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t type, uint32_t size, uint16_t width, uint16_t height, uint16_t packets, uint8_t payload, uint8_t jpg_quality) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, size); - _mav_put_uint16_t(buf, 4, width); - _mav_put_uint16_t(buf, 6, height); - _mav_put_uint16_t(buf, 8, packets); - _mav_put_uint8_t(buf, 10, type); - _mav_put_uint8_t(buf, 11, payload); - _mav_put_uint8_t(buf, 12, jpg_quality); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE, buf, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_MIN_LEN, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_CRC); -#else - mavlink_data_transmission_handshake_t *packet = (mavlink_data_transmission_handshake_t *)msgbuf; - packet->size = size; - packet->width = width; - packet->height = height; - packet->packets = packets; - packet->type = type; - packet->payload = payload; - packet->jpg_quality = jpg_quality; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE, (const char *)packet, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_MIN_LEN, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_CRC); -#endif -} -#endif - -#endif - -// MESSAGE DATA_TRANSMISSION_HANDSHAKE UNPACKING - - -/** - * @brief Get field type from data_transmission_handshake message - * - * @return Type of requested/acknowledged data. - */ -static inline uint8_t mavlink_msg_data_transmission_handshake_get_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 10); -} - -/** - * @brief Get field size from data_transmission_handshake message - * - * @return [bytes] total data size (set on ACK only). - */ -static inline uint32_t mavlink_msg_data_transmission_handshake_get_size(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field width from data_transmission_handshake message - * - * @return Width of a matrix or image. - */ -static inline uint16_t mavlink_msg_data_transmission_handshake_get_width(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 4); -} - -/** - * @brief Get field height from data_transmission_handshake message - * - * @return Height of a matrix or image. - */ -static inline uint16_t mavlink_msg_data_transmission_handshake_get_height(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 6); -} - -/** - * @brief Get field packets from data_transmission_handshake message - * - * @return Number of packets being sent (set on ACK only). - */ -static inline uint16_t mavlink_msg_data_transmission_handshake_get_packets(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 8); -} - -/** - * @brief Get field payload from data_transmission_handshake message - * - * @return [bytes] Payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only). - */ -static inline uint8_t mavlink_msg_data_transmission_handshake_get_payload(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 11); -} - -/** - * @brief Get field jpg_quality from data_transmission_handshake message - * - * @return [%] JPEG quality. Values: [1-100]. - */ -static inline uint8_t mavlink_msg_data_transmission_handshake_get_jpg_quality(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 12); -} - -/** - * @brief Decode a data_transmission_handshake message into a struct - * - * @param msg The message to decode - * @param data_transmission_handshake C-struct to decode the message contents into - */ -static inline void mavlink_msg_data_transmission_handshake_decode(const mavlink_message_t* msg, mavlink_data_transmission_handshake_t* data_transmission_handshake) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - data_transmission_handshake->size = mavlink_msg_data_transmission_handshake_get_size(msg); - data_transmission_handshake->width = mavlink_msg_data_transmission_handshake_get_width(msg); - data_transmission_handshake->height = mavlink_msg_data_transmission_handshake_get_height(msg); - data_transmission_handshake->packets = mavlink_msg_data_transmission_handshake_get_packets(msg); - data_transmission_handshake->type = mavlink_msg_data_transmission_handshake_get_type(msg); - data_transmission_handshake->payload = mavlink_msg_data_transmission_handshake_get_payload(msg); - data_transmission_handshake->jpg_quality = mavlink_msg_data_transmission_handshake_get_jpg_quality(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN? msg->len : MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN; - memset(data_transmission_handshake, 0, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN); - memcpy(data_transmission_handshake, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_debug.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_debug.h deleted file mode 100644 index 57884d84..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_debug.h +++ /dev/null @@ -1,263 +0,0 @@ -#pragma once -// MESSAGE DEBUG PACKING - -#define MAVLINK_MSG_ID_DEBUG 254 - - -typedef struct __mavlink_debug_t { - uint32_t time_boot_ms; /*< [ms] Timestamp (time since system boot).*/ - float value; /*< DEBUG value*/ - uint8_t ind; /*< index of debug variable*/ -} mavlink_debug_t; - -#define MAVLINK_MSG_ID_DEBUG_LEN 9 -#define MAVLINK_MSG_ID_DEBUG_MIN_LEN 9 -#define MAVLINK_MSG_ID_254_LEN 9 -#define MAVLINK_MSG_ID_254_MIN_LEN 9 - -#define MAVLINK_MSG_ID_DEBUG_CRC 46 -#define MAVLINK_MSG_ID_254_CRC 46 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_DEBUG { \ - 254, \ - "DEBUG", \ - 3, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_debug_t, time_boot_ms) }, \ - { "ind", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_debug_t, ind) }, \ - { "value", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_debug_t, value) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_DEBUG { \ - "DEBUG", \ - 3, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_debug_t, time_boot_ms) }, \ - { "ind", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_debug_t, ind) }, \ - { "value", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_debug_t, value) }, \ - } \ -} -#endif - -/** - * @brief Pack a debug message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param time_boot_ms [ms] Timestamp (time since system boot). - * @param ind index of debug variable - * @param value DEBUG value - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_debug_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint32_t time_boot_ms, uint8_t ind, float value) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_DEBUG_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, value); - _mav_put_uint8_t(buf, 8, ind); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DEBUG_LEN); -#else - mavlink_debug_t packet; - packet.time_boot_ms = time_boot_ms; - packet.value = value; - packet.ind = ind; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DEBUG_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_DEBUG; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DEBUG_MIN_LEN, MAVLINK_MSG_ID_DEBUG_LEN, MAVLINK_MSG_ID_DEBUG_CRC); -} - -/** - * @brief Pack a debug message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_boot_ms [ms] Timestamp (time since system boot). - * @param ind index of debug variable - * @param value DEBUG value - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_debug_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint32_t time_boot_ms,uint8_t ind,float value) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_DEBUG_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, value); - _mav_put_uint8_t(buf, 8, ind); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DEBUG_LEN); -#else - mavlink_debug_t packet; - packet.time_boot_ms = time_boot_ms; - packet.value = value; - packet.ind = ind; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DEBUG_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_DEBUG; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DEBUG_MIN_LEN, MAVLINK_MSG_ID_DEBUG_LEN, MAVLINK_MSG_ID_DEBUG_CRC); -} - -/** - * @brief Encode a debug struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param debug C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_debug_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_debug_t* debug) -{ - return mavlink_msg_debug_pack(system_id, component_id, msg, debug->time_boot_ms, debug->ind, debug->value); -} - -/** - * @brief Encode a debug struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param debug C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_debug_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_debug_t* debug) -{ - return mavlink_msg_debug_pack_chan(system_id, component_id, chan, msg, debug->time_boot_ms, debug->ind, debug->value); -} - -/** - * @brief Send a debug message - * @param chan MAVLink channel to send the message - * - * @param time_boot_ms [ms] Timestamp (time since system boot). - * @param ind index of debug variable - * @param value DEBUG value - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_debug_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t ind, float value) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_DEBUG_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, value); - _mav_put_uint8_t(buf, 8, ind); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG, buf, MAVLINK_MSG_ID_DEBUG_MIN_LEN, MAVLINK_MSG_ID_DEBUG_LEN, MAVLINK_MSG_ID_DEBUG_CRC); -#else - mavlink_debug_t packet; - packet.time_boot_ms = time_boot_ms; - packet.value = value; - packet.ind = ind; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG, (const char *)&packet, MAVLINK_MSG_ID_DEBUG_MIN_LEN, MAVLINK_MSG_ID_DEBUG_LEN, MAVLINK_MSG_ID_DEBUG_CRC); -#endif -} - -/** - * @brief Send a debug message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_debug_send_struct(mavlink_channel_t chan, const mavlink_debug_t* debug) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_debug_send(chan, debug->time_boot_ms, debug->ind, debug->value); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG, (const char *)debug, MAVLINK_MSG_ID_DEBUG_MIN_LEN, MAVLINK_MSG_ID_DEBUG_LEN, MAVLINK_MSG_ID_DEBUG_CRC); -#endif -} - -#if MAVLINK_MSG_ID_DEBUG_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_debug_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t ind, float value) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, value); - _mav_put_uint8_t(buf, 8, ind); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG, buf, MAVLINK_MSG_ID_DEBUG_MIN_LEN, MAVLINK_MSG_ID_DEBUG_LEN, MAVLINK_MSG_ID_DEBUG_CRC); -#else - mavlink_debug_t *packet = (mavlink_debug_t *)msgbuf; - packet->time_boot_ms = time_boot_ms; - packet->value = value; - packet->ind = ind; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG, (const char *)packet, MAVLINK_MSG_ID_DEBUG_MIN_LEN, MAVLINK_MSG_ID_DEBUG_LEN, MAVLINK_MSG_ID_DEBUG_CRC); -#endif -} -#endif - -#endif - -// MESSAGE DEBUG UNPACKING - - -/** - * @brief Get field time_boot_ms from debug message - * - * @return [ms] Timestamp (time since system boot). - */ -static inline uint32_t mavlink_msg_debug_get_time_boot_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field ind from debug message - * - * @return index of debug variable - */ -static inline uint8_t mavlink_msg_debug_get_ind(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 8); -} - -/** - * @brief Get field value from debug message - * - * @return DEBUG value - */ -static inline float mavlink_msg_debug_get_value(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 4); -} - -/** - * @brief Decode a debug message into a struct - * - * @param msg The message to decode - * @param debug C-struct to decode the message contents into - */ -static inline void mavlink_msg_debug_decode(const mavlink_message_t* msg, mavlink_debug_t* debug) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - debug->time_boot_ms = mavlink_msg_debug_get_time_boot_ms(msg); - debug->value = mavlink_msg_debug_get_value(msg); - debug->ind = mavlink_msg_debug_get_ind(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_DEBUG_LEN? msg->len : MAVLINK_MSG_ID_DEBUG_LEN; - memset(debug, 0, MAVLINK_MSG_ID_DEBUG_LEN); - memcpy(debug, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_debug_float_array.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_debug_float_array.h deleted file mode 100644 index f18063e6..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_debug_float_array.h +++ /dev/null @@ -1,281 +0,0 @@ -#pragma once -// MESSAGE DEBUG_FLOAT_ARRAY PACKING - -#define MAVLINK_MSG_ID_DEBUG_FLOAT_ARRAY 350 - - -typedef struct __mavlink_debug_float_array_t { - uint64_t time_usec; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/ - uint16_t array_id; /*< Unique ID used to discriminate between arrays*/ - char name[10]; /*< Name, for human-friendly display in a Ground Control Station*/ - float data[58]; /*< data*/ -} mavlink_debug_float_array_t; - -#define MAVLINK_MSG_ID_DEBUG_FLOAT_ARRAY_LEN 252 -#define MAVLINK_MSG_ID_DEBUG_FLOAT_ARRAY_MIN_LEN 20 -#define MAVLINK_MSG_ID_350_LEN 252 -#define MAVLINK_MSG_ID_350_MIN_LEN 20 - -#define MAVLINK_MSG_ID_DEBUG_FLOAT_ARRAY_CRC 232 -#define MAVLINK_MSG_ID_350_CRC 232 - -#define MAVLINK_MSG_DEBUG_FLOAT_ARRAY_FIELD_NAME_LEN 10 -#define MAVLINK_MSG_DEBUG_FLOAT_ARRAY_FIELD_DATA_LEN 58 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_DEBUG_FLOAT_ARRAY { \ - 350, \ - "DEBUG_FLOAT_ARRAY", \ - 4, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_debug_float_array_t, time_usec) }, \ - { "name", NULL, MAVLINK_TYPE_CHAR, 10, 10, offsetof(mavlink_debug_float_array_t, name) }, \ - { "array_id", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_debug_float_array_t, array_id) }, \ - { "data", NULL, MAVLINK_TYPE_FLOAT, 58, 20, offsetof(mavlink_debug_float_array_t, data) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_DEBUG_FLOAT_ARRAY { \ - "DEBUG_FLOAT_ARRAY", \ - 4, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_debug_float_array_t, time_usec) }, \ - { "name", NULL, MAVLINK_TYPE_CHAR, 10, 10, offsetof(mavlink_debug_float_array_t, name) }, \ - { "array_id", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_debug_float_array_t, array_id) }, \ - { "data", NULL, MAVLINK_TYPE_FLOAT, 58, 20, offsetof(mavlink_debug_float_array_t, data) }, \ - } \ -} -#endif - -/** - * @brief Pack a debug_float_array message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @param name Name, for human-friendly display in a Ground Control Station - * @param array_id Unique ID used to discriminate between arrays - * @param data data - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_debug_float_array_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint64_t time_usec, const char *name, uint16_t array_id, const float *data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_DEBUG_FLOAT_ARRAY_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint16_t(buf, 8, array_id); - _mav_put_char_array(buf, 10, name, 10); - _mav_put_float_array(buf, 20, data, 58); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DEBUG_FLOAT_ARRAY_LEN); -#else - mavlink_debug_float_array_t packet; - packet.time_usec = time_usec; - packet.array_id = array_id; - mav_array_memcpy(packet.name, name, sizeof(char)*10); - mav_array_memcpy(packet.data, data, sizeof(float)*58); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DEBUG_FLOAT_ARRAY_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_DEBUG_FLOAT_ARRAY; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DEBUG_FLOAT_ARRAY_MIN_LEN, MAVLINK_MSG_ID_DEBUG_FLOAT_ARRAY_LEN, MAVLINK_MSG_ID_DEBUG_FLOAT_ARRAY_CRC); -} - -/** - * @brief Pack a debug_float_array message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @param name Name, for human-friendly display in a Ground Control Station - * @param array_id Unique ID used to discriminate between arrays - * @param data data - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_debug_float_array_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint64_t time_usec,const char *name,uint16_t array_id,const float *data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_DEBUG_FLOAT_ARRAY_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint16_t(buf, 8, array_id); - _mav_put_char_array(buf, 10, name, 10); - _mav_put_float_array(buf, 20, data, 58); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DEBUG_FLOAT_ARRAY_LEN); -#else - mavlink_debug_float_array_t packet; - packet.time_usec = time_usec; - packet.array_id = array_id; - mav_array_memcpy(packet.name, name, sizeof(char)*10); - mav_array_memcpy(packet.data, data, sizeof(float)*58); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DEBUG_FLOAT_ARRAY_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_DEBUG_FLOAT_ARRAY; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DEBUG_FLOAT_ARRAY_MIN_LEN, MAVLINK_MSG_ID_DEBUG_FLOAT_ARRAY_LEN, MAVLINK_MSG_ID_DEBUG_FLOAT_ARRAY_CRC); -} - -/** - * @brief Encode a debug_float_array struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param debug_float_array C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_debug_float_array_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_debug_float_array_t* debug_float_array) -{ - return mavlink_msg_debug_float_array_pack(system_id, component_id, msg, debug_float_array->time_usec, debug_float_array->name, debug_float_array->array_id, debug_float_array->data); -} - -/** - * @brief Encode a debug_float_array struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param debug_float_array C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_debug_float_array_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_debug_float_array_t* debug_float_array) -{ - return mavlink_msg_debug_float_array_pack_chan(system_id, component_id, chan, msg, debug_float_array->time_usec, debug_float_array->name, debug_float_array->array_id, debug_float_array->data); -} - -/** - * @brief Send a debug_float_array message - * @param chan MAVLink channel to send the message - * - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @param name Name, for human-friendly display in a Ground Control Station - * @param array_id Unique ID used to discriminate between arrays - * @param data data - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_debug_float_array_send(mavlink_channel_t chan, uint64_t time_usec, const char *name, uint16_t array_id, const float *data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_DEBUG_FLOAT_ARRAY_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint16_t(buf, 8, array_id); - _mav_put_char_array(buf, 10, name, 10); - _mav_put_float_array(buf, 20, data, 58); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG_FLOAT_ARRAY, buf, MAVLINK_MSG_ID_DEBUG_FLOAT_ARRAY_MIN_LEN, MAVLINK_MSG_ID_DEBUG_FLOAT_ARRAY_LEN, MAVLINK_MSG_ID_DEBUG_FLOAT_ARRAY_CRC); -#else - mavlink_debug_float_array_t packet; - packet.time_usec = time_usec; - packet.array_id = array_id; - mav_array_memcpy(packet.name, name, sizeof(char)*10); - mav_array_memcpy(packet.data, data, sizeof(float)*58); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG_FLOAT_ARRAY, (const char *)&packet, MAVLINK_MSG_ID_DEBUG_FLOAT_ARRAY_MIN_LEN, MAVLINK_MSG_ID_DEBUG_FLOAT_ARRAY_LEN, MAVLINK_MSG_ID_DEBUG_FLOAT_ARRAY_CRC); -#endif -} - -/** - * @brief Send a debug_float_array message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_debug_float_array_send_struct(mavlink_channel_t chan, const mavlink_debug_float_array_t* debug_float_array) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_debug_float_array_send(chan, debug_float_array->time_usec, debug_float_array->name, debug_float_array->array_id, debug_float_array->data); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG_FLOAT_ARRAY, (const char *)debug_float_array, MAVLINK_MSG_ID_DEBUG_FLOAT_ARRAY_MIN_LEN, MAVLINK_MSG_ID_DEBUG_FLOAT_ARRAY_LEN, MAVLINK_MSG_ID_DEBUG_FLOAT_ARRAY_CRC); -#endif -} - -#if MAVLINK_MSG_ID_DEBUG_FLOAT_ARRAY_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_debug_float_array_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, const char *name, uint16_t array_id, const float *data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint16_t(buf, 8, array_id); - _mav_put_char_array(buf, 10, name, 10); - _mav_put_float_array(buf, 20, data, 58); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG_FLOAT_ARRAY, buf, MAVLINK_MSG_ID_DEBUG_FLOAT_ARRAY_MIN_LEN, MAVLINK_MSG_ID_DEBUG_FLOAT_ARRAY_LEN, MAVLINK_MSG_ID_DEBUG_FLOAT_ARRAY_CRC); -#else - mavlink_debug_float_array_t *packet = (mavlink_debug_float_array_t *)msgbuf; - packet->time_usec = time_usec; - packet->array_id = array_id; - mav_array_memcpy(packet->name, name, sizeof(char)*10); - mav_array_memcpy(packet->data, data, sizeof(float)*58); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG_FLOAT_ARRAY, (const char *)packet, MAVLINK_MSG_ID_DEBUG_FLOAT_ARRAY_MIN_LEN, MAVLINK_MSG_ID_DEBUG_FLOAT_ARRAY_LEN, MAVLINK_MSG_ID_DEBUG_FLOAT_ARRAY_CRC); -#endif -} -#endif - -#endif - -// MESSAGE DEBUG_FLOAT_ARRAY UNPACKING - - -/** - * @brief Get field time_usec from debug_float_array message - * - * @return [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - */ -static inline uint64_t mavlink_msg_debug_float_array_get_time_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field name from debug_float_array message - * - * @return Name, for human-friendly display in a Ground Control Station - */ -static inline uint16_t mavlink_msg_debug_float_array_get_name(const mavlink_message_t* msg, char *name) -{ - return _MAV_RETURN_char_array(msg, name, 10, 10); -} - -/** - * @brief Get field array_id from debug_float_array message - * - * @return Unique ID used to discriminate between arrays - */ -static inline uint16_t mavlink_msg_debug_float_array_get_array_id(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 8); -} - -/** - * @brief Get field data from debug_float_array message - * - * @return data - */ -static inline uint16_t mavlink_msg_debug_float_array_get_data(const mavlink_message_t* msg, float *data) -{ - return _MAV_RETURN_float_array(msg, data, 58, 20); -} - -/** - * @brief Decode a debug_float_array message into a struct - * - * @param msg The message to decode - * @param debug_float_array C-struct to decode the message contents into - */ -static inline void mavlink_msg_debug_float_array_decode(const mavlink_message_t* msg, mavlink_debug_float_array_t* debug_float_array) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - debug_float_array->time_usec = mavlink_msg_debug_float_array_get_time_usec(msg); - debug_float_array->array_id = mavlink_msg_debug_float_array_get_array_id(msg); - mavlink_msg_debug_float_array_get_name(msg, debug_float_array->name); - mavlink_msg_debug_float_array_get_data(msg, debug_float_array->data); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_DEBUG_FLOAT_ARRAY_LEN? msg->len : MAVLINK_MSG_ID_DEBUG_FLOAT_ARRAY_LEN; - memset(debug_float_array, 0, MAVLINK_MSG_ID_DEBUG_FLOAT_ARRAY_LEN); - memcpy(debug_float_array, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_debug_vect.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_debug_vect.h deleted file mode 100644 index bef35f8c..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_debug_vect.h +++ /dev/null @@ -1,305 +0,0 @@ -#pragma once -// MESSAGE DEBUG_VECT PACKING - -#define MAVLINK_MSG_ID_DEBUG_VECT 250 - - -typedef struct __mavlink_debug_vect_t { - uint64_t time_usec; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/ - float x; /*< x*/ - float y; /*< y*/ - float z; /*< z*/ - char name[10]; /*< Name*/ -} mavlink_debug_vect_t; - -#define MAVLINK_MSG_ID_DEBUG_VECT_LEN 30 -#define MAVLINK_MSG_ID_DEBUG_VECT_MIN_LEN 30 -#define MAVLINK_MSG_ID_250_LEN 30 -#define MAVLINK_MSG_ID_250_MIN_LEN 30 - -#define MAVLINK_MSG_ID_DEBUG_VECT_CRC 49 -#define MAVLINK_MSG_ID_250_CRC 49 - -#define MAVLINK_MSG_DEBUG_VECT_FIELD_NAME_LEN 10 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_DEBUG_VECT { \ - 250, \ - "DEBUG_VECT", \ - 5, \ - { { "name", NULL, MAVLINK_TYPE_CHAR, 10, 20, offsetof(mavlink_debug_vect_t, name) }, \ - { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_debug_vect_t, time_usec) }, \ - { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_debug_vect_t, x) }, \ - { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_debug_vect_t, y) }, \ - { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_debug_vect_t, z) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_DEBUG_VECT { \ - "DEBUG_VECT", \ - 5, \ - { { "name", NULL, MAVLINK_TYPE_CHAR, 10, 20, offsetof(mavlink_debug_vect_t, name) }, \ - { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_debug_vect_t, time_usec) }, \ - { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_debug_vect_t, x) }, \ - { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_debug_vect_t, y) }, \ - { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_debug_vect_t, z) }, \ - } \ -} -#endif - -/** - * @brief Pack a debug_vect message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param name Name - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @param x x - * @param y y - * @param z z - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_debug_vect_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - const char *name, uint64_t time_usec, float x, float y, float z) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_DEBUG_VECT_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, x); - _mav_put_float(buf, 12, y); - _mav_put_float(buf, 16, z); - _mav_put_char_array(buf, 20, name, 10); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DEBUG_VECT_LEN); -#else - mavlink_debug_vect_t packet; - packet.time_usec = time_usec; - packet.x = x; - packet.y = y; - packet.z = z; - mav_array_memcpy(packet.name, name, sizeof(char)*10); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DEBUG_VECT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_DEBUG_VECT; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DEBUG_VECT_MIN_LEN, MAVLINK_MSG_ID_DEBUG_VECT_LEN, MAVLINK_MSG_ID_DEBUG_VECT_CRC); -} - -/** - * @brief Pack a debug_vect message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param name Name - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @param x x - * @param y y - * @param z z - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_debug_vect_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - const char *name,uint64_t time_usec,float x,float y,float z) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_DEBUG_VECT_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, x); - _mav_put_float(buf, 12, y); - _mav_put_float(buf, 16, z); - _mav_put_char_array(buf, 20, name, 10); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DEBUG_VECT_LEN); -#else - mavlink_debug_vect_t packet; - packet.time_usec = time_usec; - packet.x = x; - packet.y = y; - packet.z = z; - mav_array_memcpy(packet.name, name, sizeof(char)*10); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DEBUG_VECT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_DEBUG_VECT; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DEBUG_VECT_MIN_LEN, MAVLINK_MSG_ID_DEBUG_VECT_LEN, MAVLINK_MSG_ID_DEBUG_VECT_CRC); -} - -/** - * @brief Encode a debug_vect struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param debug_vect C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_debug_vect_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_debug_vect_t* debug_vect) -{ - return mavlink_msg_debug_vect_pack(system_id, component_id, msg, debug_vect->name, debug_vect->time_usec, debug_vect->x, debug_vect->y, debug_vect->z); -} - -/** - * @brief Encode a debug_vect struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param debug_vect C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_debug_vect_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_debug_vect_t* debug_vect) -{ - return mavlink_msg_debug_vect_pack_chan(system_id, component_id, chan, msg, debug_vect->name, debug_vect->time_usec, debug_vect->x, debug_vect->y, debug_vect->z); -} - -/** - * @brief Send a debug_vect message - * @param chan MAVLink channel to send the message - * - * @param name Name - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @param x x - * @param y y - * @param z z - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_debug_vect_send(mavlink_channel_t chan, const char *name, uint64_t time_usec, float x, float y, float z) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_DEBUG_VECT_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, x); - _mav_put_float(buf, 12, y); - _mav_put_float(buf, 16, z); - _mav_put_char_array(buf, 20, name, 10); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG_VECT, buf, MAVLINK_MSG_ID_DEBUG_VECT_MIN_LEN, MAVLINK_MSG_ID_DEBUG_VECT_LEN, MAVLINK_MSG_ID_DEBUG_VECT_CRC); -#else - mavlink_debug_vect_t packet; - packet.time_usec = time_usec; - packet.x = x; - packet.y = y; - packet.z = z; - mav_array_memcpy(packet.name, name, sizeof(char)*10); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG_VECT, (const char *)&packet, MAVLINK_MSG_ID_DEBUG_VECT_MIN_LEN, MAVLINK_MSG_ID_DEBUG_VECT_LEN, MAVLINK_MSG_ID_DEBUG_VECT_CRC); -#endif -} - -/** - * @brief Send a debug_vect message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_debug_vect_send_struct(mavlink_channel_t chan, const mavlink_debug_vect_t* debug_vect) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_debug_vect_send(chan, debug_vect->name, debug_vect->time_usec, debug_vect->x, debug_vect->y, debug_vect->z); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG_VECT, (const char *)debug_vect, MAVLINK_MSG_ID_DEBUG_VECT_MIN_LEN, MAVLINK_MSG_ID_DEBUG_VECT_LEN, MAVLINK_MSG_ID_DEBUG_VECT_CRC); -#endif -} - -#if MAVLINK_MSG_ID_DEBUG_VECT_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_debug_vect_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, const char *name, uint64_t time_usec, float x, float y, float z) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, x); - _mav_put_float(buf, 12, y); - _mav_put_float(buf, 16, z); - _mav_put_char_array(buf, 20, name, 10); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG_VECT, buf, MAVLINK_MSG_ID_DEBUG_VECT_MIN_LEN, MAVLINK_MSG_ID_DEBUG_VECT_LEN, MAVLINK_MSG_ID_DEBUG_VECT_CRC); -#else - mavlink_debug_vect_t *packet = (mavlink_debug_vect_t *)msgbuf; - packet->time_usec = time_usec; - packet->x = x; - packet->y = y; - packet->z = z; - mav_array_memcpy(packet->name, name, sizeof(char)*10); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG_VECT, (const char *)packet, MAVLINK_MSG_ID_DEBUG_VECT_MIN_LEN, MAVLINK_MSG_ID_DEBUG_VECT_LEN, MAVLINK_MSG_ID_DEBUG_VECT_CRC); -#endif -} -#endif - -#endif - -// MESSAGE DEBUG_VECT UNPACKING - - -/** - * @brief Get field name from debug_vect message - * - * @return Name - */ -static inline uint16_t mavlink_msg_debug_vect_get_name(const mavlink_message_t* msg, char *name) -{ - return _MAV_RETURN_char_array(msg, name, 10, 20); -} - -/** - * @brief Get field time_usec from debug_vect message - * - * @return [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - */ -static inline uint64_t mavlink_msg_debug_vect_get_time_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field x from debug_vect message - * - * @return x - */ -static inline float mavlink_msg_debug_vect_get_x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field y from debug_vect message - * - * @return y - */ -static inline float mavlink_msg_debug_vect_get_y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field z from debug_vect message - * - * @return z - */ -static inline float mavlink_msg_debug_vect_get_z(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Decode a debug_vect message into a struct - * - * @param msg The message to decode - * @param debug_vect C-struct to decode the message contents into - */ -static inline void mavlink_msg_debug_vect_decode(const mavlink_message_t* msg, mavlink_debug_vect_t* debug_vect) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - debug_vect->time_usec = mavlink_msg_debug_vect_get_time_usec(msg); - debug_vect->x = mavlink_msg_debug_vect_get_x(msg); - debug_vect->y = mavlink_msg_debug_vect_get_y(msg); - debug_vect->z = mavlink_msg_debug_vect_get_z(msg); - mavlink_msg_debug_vect_get_name(msg, debug_vect->name); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_DEBUG_VECT_LEN? msg->len : MAVLINK_MSG_ID_DEBUG_VECT_LEN; - memset(debug_vect, 0, MAVLINK_MSG_ID_DEBUG_VECT_LEN); - memcpy(debug_vect, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_distance_sensor.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_distance_sensor.h deleted file mode 100644 index 601257ca..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_distance_sensor.h +++ /dev/null @@ -1,480 +0,0 @@ -#pragma once -// MESSAGE DISTANCE_SENSOR PACKING - -#define MAVLINK_MSG_ID_DISTANCE_SENSOR 132 - -MAVPACKED( -typedef struct __mavlink_distance_sensor_t { - uint32_t time_boot_ms; /*< [ms] Timestamp (time since system boot).*/ - uint16_t min_distance; /*< [cm] Minimum distance the sensor can measure*/ - uint16_t max_distance; /*< [cm] Maximum distance the sensor can measure*/ - uint16_t current_distance; /*< [cm] Current distance reading*/ - uint8_t type; /*< Type of distance sensor.*/ - uint8_t id; /*< Onboard ID of the sensor*/ - uint8_t orientation; /*< Direction the sensor faces. downward-facing: ROTATION_PITCH_270, upward-facing: ROTATION_PITCH_90, backward-facing: ROTATION_PITCH_180, forward-facing: ROTATION_NONE, left-facing: ROTATION_YAW_90, right-facing: ROTATION_YAW_270*/ - uint8_t covariance; /*< [cm^2] Measurement variance. Max standard deviation is 6cm. UINT8_MAX if unknown.*/ - float horizontal_fov; /*< [rad] Horizontal Field of View (angle) where the distance measurement is valid and the field of view is known. Otherwise this is set to 0.*/ - float vertical_fov; /*< [rad] Vertical Field of View (angle) where the distance measurement is valid and the field of view is known. Otherwise this is set to 0.*/ - float quaternion[4]; /*< Quaternion of the sensor orientation in vehicle body frame (w, x, y, z order, zero-rotation is 1, 0, 0, 0). Zero-rotation is along the vehicle body x-axis. This field is required if the orientation is set to MAV_SENSOR_ROTATION_CUSTOM. Set it to 0 if invalid."*/ - uint8_t signal_quality; /*< [%] Signal quality of the sensor. Specific to each sensor type, representing the relation of the signal strength with the target reflectivity, distance, size or aspect, but normalised as a percentage. 0 = unknown/unset signal quality, 1 = invalid signal, 100 = perfect signal.*/ -}) mavlink_distance_sensor_t; - -#define MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN 39 -#define MAVLINK_MSG_ID_DISTANCE_SENSOR_MIN_LEN 14 -#define MAVLINK_MSG_ID_132_LEN 39 -#define MAVLINK_MSG_ID_132_MIN_LEN 14 - -#define MAVLINK_MSG_ID_DISTANCE_SENSOR_CRC 85 -#define MAVLINK_MSG_ID_132_CRC 85 - -#define MAVLINK_MSG_DISTANCE_SENSOR_FIELD_QUATERNION_LEN 4 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_DISTANCE_SENSOR { \ - 132, \ - "DISTANCE_SENSOR", \ - 12, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_distance_sensor_t, time_boot_ms) }, \ - { "min_distance", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_distance_sensor_t, min_distance) }, \ - { "max_distance", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_distance_sensor_t, max_distance) }, \ - { "current_distance", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_distance_sensor_t, current_distance) }, \ - { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_distance_sensor_t, type) }, \ - { "id", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_distance_sensor_t, id) }, \ - { "orientation", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_distance_sensor_t, orientation) }, \ - { "covariance", NULL, MAVLINK_TYPE_UINT8_T, 0, 13, offsetof(mavlink_distance_sensor_t, covariance) }, \ - { "horizontal_fov", NULL, MAVLINK_TYPE_FLOAT, 0, 14, offsetof(mavlink_distance_sensor_t, horizontal_fov) }, \ - { "vertical_fov", NULL, MAVLINK_TYPE_FLOAT, 0, 18, offsetof(mavlink_distance_sensor_t, vertical_fov) }, \ - { "quaternion", NULL, MAVLINK_TYPE_FLOAT, 4, 22, offsetof(mavlink_distance_sensor_t, quaternion) }, \ - { "signal_quality", NULL, MAVLINK_TYPE_UINT8_T, 0, 38, offsetof(mavlink_distance_sensor_t, signal_quality) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_DISTANCE_SENSOR { \ - "DISTANCE_SENSOR", \ - 12, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_distance_sensor_t, time_boot_ms) }, \ - { "min_distance", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_distance_sensor_t, min_distance) }, \ - { "max_distance", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_distance_sensor_t, max_distance) }, \ - { "current_distance", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_distance_sensor_t, current_distance) }, \ - { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_distance_sensor_t, type) }, \ - { "id", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_distance_sensor_t, id) }, \ - { "orientation", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_distance_sensor_t, orientation) }, \ - { "covariance", NULL, MAVLINK_TYPE_UINT8_T, 0, 13, offsetof(mavlink_distance_sensor_t, covariance) }, \ - { "horizontal_fov", NULL, MAVLINK_TYPE_FLOAT, 0, 14, offsetof(mavlink_distance_sensor_t, horizontal_fov) }, \ - { "vertical_fov", NULL, MAVLINK_TYPE_FLOAT, 0, 18, offsetof(mavlink_distance_sensor_t, vertical_fov) }, \ - { "quaternion", NULL, MAVLINK_TYPE_FLOAT, 4, 22, offsetof(mavlink_distance_sensor_t, quaternion) }, \ - { "signal_quality", NULL, MAVLINK_TYPE_UINT8_T, 0, 38, offsetof(mavlink_distance_sensor_t, signal_quality) }, \ - } \ -} -#endif - -/** - * @brief Pack a distance_sensor message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param time_boot_ms [ms] Timestamp (time since system boot). - * @param min_distance [cm] Minimum distance the sensor can measure - * @param max_distance [cm] Maximum distance the sensor can measure - * @param current_distance [cm] Current distance reading - * @param type Type of distance sensor. - * @param id Onboard ID of the sensor - * @param orientation Direction the sensor faces. downward-facing: ROTATION_PITCH_270, upward-facing: ROTATION_PITCH_90, backward-facing: ROTATION_PITCH_180, forward-facing: ROTATION_NONE, left-facing: ROTATION_YAW_90, right-facing: ROTATION_YAW_270 - * @param covariance [cm^2] Measurement variance. Max standard deviation is 6cm. UINT8_MAX if unknown. - * @param horizontal_fov [rad] Horizontal Field of View (angle) where the distance measurement is valid and the field of view is known. Otherwise this is set to 0. - * @param vertical_fov [rad] Vertical Field of View (angle) where the distance measurement is valid and the field of view is known. Otherwise this is set to 0. - * @param quaternion Quaternion of the sensor orientation in vehicle body frame (w, x, y, z order, zero-rotation is 1, 0, 0, 0). Zero-rotation is along the vehicle body x-axis. This field is required if the orientation is set to MAV_SENSOR_ROTATION_CUSTOM. Set it to 0 if invalid." - * @param signal_quality [%] Signal quality of the sensor. Specific to each sensor type, representing the relation of the signal strength with the target reflectivity, distance, size or aspect, but normalised as a percentage. 0 = unknown/unset signal quality, 1 = invalid signal, 100 = perfect signal. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_distance_sensor_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint32_t time_boot_ms, uint16_t min_distance, uint16_t max_distance, uint16_t current_distance, uint8_t type, uint8_t id, uint8_t orientation, uint8_t covariance, float horizontal_fov, float vertical_fov, const float *quaternion, uint8_t signal_quality) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_uint16_t(buf, 4, min_distance); - _mav_put_uint16_t(buf, 6, max_distance); - _mav_put_uint16_t(buf, 8, current_distance); - _mav_put_uint8_t(buf, 10, type); - _mav_put_uint8_t(buf, 11, id); - _mav_put_uint8_t(buf, 12, orientation); - _mav_put_uint8_t(buf, 13, covariance); - _mav_put_float(buf, 14, horizontal_fov); - _mav_put_float(buf, 18, vertical_fov); - _mav_put_uint8_t(buf, 38, signal_quality); - _mav_put_float_array(buf, 22, quaternion, 4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN); -#else - mavlink_distance_sensor_t packet; - packet.time_boot_ms = time_boot_ms; - packet.min_distance = min_distance; - packet.max_distance = max_distance; - packet.current_distance = current_distance; - packet.type = type; - packet.id = id; - packet.orientation = orientation; - packet.covariance = covariance; - packet.horizontal_fov = horizontal_fov; - packet.vertical_fov = vertical_fov; - packet.signal_quality = signal_quality; - mav_array_memcpy(packet.quaternion, quaternion, sizeof(float)*4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_DISTANCE_SENSOR; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DISTANCE_SENSOR_MIN_LEN, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN, MAVLINK_MSG_ID_DISTANCE_SENSOR_CRC); -} - -/** - * @brief Pack a distance_sensor message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_boot_ms [ms] Timestamp (time since system boot). - * @param min_distance [cm] Minimum distance the sensor can measure - * @param max_distance [cm] Maximum distance the sensor can measure - * @param current_distance [cm] Current distance reading - * @param type Type of distance sensor. - * @param id Onboard ID of the sensor - * @param orientation Direction the sensor faces. downward-facing: ROTATION_PITCH_270, upward-facing: ROTATION_PITCH_90, backward-facing: ROTATION_PITCH_180, forward-facing: ROTATION_NONE, left-facing: ROTATION_YAW_90, right-facing: ROTATION_YAW_270 - * @param covariance [cm^2] Measurement variance. Max standard deviation is 6cm. UINT8_MAX if unknown. - * @param horizontal_fov [rad] Horizontal Field of View (angle) where the distance measurement is valid and the field of view is known. Otherwise this is set to 0. - * @param vertical_fov [rad] Vertical Field of View (angle) where the distance measurement is valid and the field of view is known. Otherwise this is set to 0. - * @param quaternion Quaternion of the sensor orientation in vehicle body frame (w, x, y, z order, zero-rotation is 1, 0, 0, 0). Zero-rotation is along the vehicle body x-axis. This field is required if the orientation is set to MAV_SENSOR_ROTATION_CUSTOM. Set it to 0 if invalid." - * @param signal_quality [%] Signal quality of the sensor. Specific to each sensor type, representing the relation of the signal strength with the target reflectivity, distance, size or aspect, but normalised as a percentage. 0 = unknown/unset signal quality, 1 = invalid signal, 100 = perfect signal. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_distance_sensor_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint32_t time_boot_ms,uint16_t min_distance,uint16_t max_distance,uint16_t current_distance,uint8_t type,uint8_t id,uint8_t orientation,uint8_t covariance,float horizontal_fov,float vertical_fov,const float *quaternion,uint8_t signal_quality) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_uint16_t(buf, 4, min_distance); - _mav_put_uint16_t(buf, 6, max_distance); - _mav_put_uint16_t(buf, 8, current_distance); - _mav_put_uint8_t(buf, 10, type); - _mav_put_uint8_t(buf, 11, id); - _mav_put_uint8_t(buf, 12, orientation); - _mav_put_uint8_t(buf, 13, covariance); - _mav_put_float(buf, 14, horizontal_fov); - _mav_put_float(buf, 18, vertical_fov); - _mav_put_uint8_t(buf, 38, signal_quality); - _mav_put_float_array(buf, 22, quaternion, 4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN); -#else - mavlink_distance_sensor_t packet; - packet.time_boot_ms = time_boot_ms; - packet.min_distance = min_distance; - packet.max_distance = max_distance; - packet.current_distance = current_distance; - packet.type = type; - packet.id = id; - packet.orientation = orientation; - packet.covariance = covariance; - packet.horizontal_fov = horizontal_fov; - packet.vertical_fov = vertical_fov; - packet.signal_quality = signal_quality; - mav_array_memcpy(packet.quaternion, quaternion, sizeof(float)*4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_DISTANCE_SENSOR; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DISTANCE_SENSOR_MIN_LEN, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN, MAVLINK_MSG_ID_DISTANCE_SENSOR_CRC); -} - -/** - * @brief Encode a distance_sensor struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param distance_sensor C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_distance_sensor_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_distance_sensor_t* distance_sensor) -{ - return mavlink_msg_distance_sensor_pack(system_id, component_id, msg, distance_sensor->time_boot_ms, distance_sensor->min_distance, distance_sensor->max_distance, distance_sensor->current_distance, distance_sensor->type, distance_sensor->id, distance_sensor->orientation, distance_sensor->covariance, distance_sensor->horizontal_fov, distance_sensor->vertical_fov, distance_sensor->quaternion, distance_sensor->signal_quality); -} - -/** - * @brief Encode a distance_sensor struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param distance_sensor C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_distance_sensor_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_distance_sensor_t* distance_sensor) -{ - return mavlink_msg_distance_sensor_pack_chan(system_id, component_id, chan, msg, distance_sensor->time_boot_ms, distance_sensor->min_distance, distance_sensor->max_distance, distance_sensor->current_distance, distance_sensor->type, distance_sensor->id, distance_sensor->orientation, distance_sensor->covariance, distance_sensor->horizontal_fov, distance_sensor->vertical_fov, distance_sensor->quaternion, distance_sensor->signal_quality); -} - -/** - * @brief Send a distance_sensor message - * @param chan MAVLink channel to send the message - * - * @param time_boot_ms [ms] Timestamp (time since system boot). - * @param min_distance [cm] Minimum distance the sensor can measure - * @param max_distance [cm] Maximum distance the sensor can measure - * @param current_distance [cm] Current distance reading - * @param type Type of distance sensor. - * @param id Onboard ID of the sensor - * @param orientation Direction the sensor faces. downward-facing: ROTATION_PITCH_270, upward-facing: ROTATION_PITCH_90, backward-facing: ROTATION_PITCH_180, forward-facing: ROTATION_NONE, left-facing: ROTATION_YAW_90, right-facing: ROTATION_YAW_270 - * @param covariance [cm^2] Measurement variance. Max standard deviation is 6cm. UINT8_MAX if unknown. - * @param horizontal_fov [rad] Horizontal Field of View (angle) where the distance measurement is valid and the field of view is known. Otherwise this is set to 0. - * @param vertical_fov [rad] Vertical Field of View (angle) where the distance measurement is valid and the field of view is known. Otherwise this is set to 0. - * @param quaternion Quaternion of the sensor orientation in vehicle body frame (w, x, y, z order, zero-rotation is 1, 0, 0, 0). Zero-rotation is along the vehicle body x-axis. This field is required if the orientation is set to MAV_SENSOR_ROTATION_CUSTOM. Set it to 0 if invalid." - * @param signal_quality [%] Signal quality of the sensor. Specific to each sensor type, representing the relation of the signal strength with the target reflectivity, distance, size or aspect, but normalised as a percentage. 0 = unknown/unset signal quality, 1 = invalid signal, 100 = perfect signal. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_distance_sensor_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint16_t min_distance, uint16_t max_distance, uint16_t current_distance, uint8_t type, uint8_t id, uint8_t orientation, uint8_t covariance, float horizontal_fov, float vertical_fov, const float *quaternion, uint8_t signal_quality) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_uint16_t(buf, 4, min_distance); - _mav_put_uint16_t(buf, 6, max_distance); - _mav_put_uint16_t(buf, 8, current_distance); - _mav_put_uint8_t(buf, 10, type); - _mav_put_uint8_t(buf, 11, id); - _mav_put_uint8_t(buf, 12, orientation); - _mav_put_uint8_t(buf, 13, covariance); - _mav_put_float(buf, 14, horizontal_fov); - _mav_put_float(buf, 18, vertical_fov); - _mav_put_uint8_t(buf, 38, signal_quality); - _mav_put_float_array(buf, 22, quaternion, 4); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DISTANCE_SENSOR, buf, MAVLINK_MSG_ID_DISTANCE_SENSOR_MIN_LEN, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN, MAVLINK_MSG_ID_DISTANCE_SENSOR_CRC); -#else - mavlink_distance_sensor_t packet; - packet.time_boot_ms = time_boot_ms; - packet.min_distance = min_distance; - packet.max_distance = max_distance; - packet.current_distance = current_distance; - packet.type = type; - packet.id = id; - packet.orientation = orientation; - packet.covariance = covariance; - packet.horizontal_fov = horizontal_fov; - packet.vertical_fov = vertical_fov; - packet.signal_quality = signal_quality; - mav_array_memcpy(packet.quaternion, quaternion, sizeof(float)*4); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DISTANCE_SENSOR, (const char *)&packet, MAVLINK_MSG_ID_DISTANCE_SENSOR_MIN_LEN, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN, MAVLINK_MSG_ID_DISTANCE_SENSOR_CRC); -#endif -} - -/** - * @brief Send a distance_sensor message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_distance_sensor_send_struct(mavlink_channel_t chan, const mavlink_distance_sensor_t* distance_sensor) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_distance_sensor_send(chan, distance_sensor->time_boot_ms, distance_sensor->min_distance, distance_sensor->max_distance, distance_sensor->current_distance, distance_sensor->type, distance_sensor->id, distance_sensor->orientation, distance_sensor->covariance, distance_sensor->horizontal_fov, distance_sensor->vertical_fov, distance_sensor->quaternion, distance_sensor->signal_quality); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DISTANCE_SENSOR, (const char *)distance_sensor, MAVLINK_MSG_ID_DISTANCE_SENSOR_MIN_LEN, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN, MAVLINK_MSG_ID_DISTANCE_SENSOR_CRC); -#endif -} - -#if MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_distance_sensor_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint16_t min_distance, uint16_t max_distance, uint16_t current_distance, uint8_t type, uint8_t id, uint8_t orientation, uint8_t covariance, float horizontal_fov, float vertical_fov, const float *quaternion, uint8_t signal_quality) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_uint16_t(buf, 4, min_distance); - _mav_put_uint16_t(buf, 6, max_distance); - _mav_put_uint16_t(buf, 8, current_distance); - _mav_put_uint8_t(buf, 10, type); - _mav_put_uint8_t(buf, 11, id); - _mav_put_uint8_t(buf, 12, orientation); - _mav_put_uint8_t(buf, 13, covariance); - _mav_put_float(buf, 14, horizontal_fov); - _mav_put_float(buf, 18, vertical_fov); - _mav_put_uint8_t(buf, 38, signal_quality); - _mav_put_float_array(buf, 22, quaternion, 4); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DISTANCE_SENSOR, buf, MAVLINK_MSG_ID_DISTANCE_SENSOR_MIN_LEN, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN, MAVLINK_MSG_ID_DISTANCE_SENSOR_CRC); -#else - mavlink_distance_sensor_t *packet = (mavlink_distance_sensor_t *)msgbuf; - packet->time_boot_ms = time_boot_ms; - packet->min_distance = min_distance; - packet->max_distance = max_distance; - packet->current_distance = current_distance; - packet->type = type; - packet->id = id; - packet->orientation = orientation; - packet->covariance = covariance; - packet->horizontal_fov = horizontal_fov; - packet->vertical_fov = vertical_fov; - packet->signal_quality = signal_quality; - mav_array_memcpy(packet->quaternion, quaternion, sizeof(float)*4); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DISTANCE_SENSOR, (const char *)packet, MAVLINK_MSG_ID_DISTANCE_SENSOR_MIN_LEN, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN, MAVLINK_MSG_ID_DISTANCE_SENSOR_CRC); -#endif -} -#endif - -#endif - -// MESSAGE DISTANCE_SENSOR UNPACKING - - -/** - * @brief Get field time_boot_ms from distance_sensor message - * - * @return [ms] Timestamp (time since system boot). - */ -static inline uint32_t mavlink_msg_distance_sensor_get_time_boot_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field min_distance from distance_sensor message - * - * @return [cm] Minimum distance the sensor can measure - */ -static inline uint16_t mavlink_msg_distance_sensor_get_min_distance(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 4); -} - -/** - * @brief Get field max_distance from distance_sensor message - * - * @return [cm] Maximum distance the sensor can measure - */ -static inline uint16_t mavlink_msg_distance_sensor_get_max_distance(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 6); -} - -/** - * @brief Get field current_distance from distance_sensor message - * - * @return [cm] Current distance reading - */ -static inline uint16_t mavlink_msg_distance_sensor_get_current_distance(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 8); -} - -/** - * @brief Get field type from distance_sensor message - * - * @return Type of distance sensor. - */ -static inline uint8_t mavlink_msg_distance_sensor_get_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 10); -} - -/** - * @brief Get field id from distance_sensor message - * - * @return Onboard ID of the sensor - */ -static inline uint8_t mavlink_msg_distance_sensor_get_id(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 11); -} - -/** - * @brief Get field orientation from distance_sensor message - * - * @return Direction the sensor faces. downward-facing: ROTATION_PITCH_270, upward-facing: ROTATION_PITCH_90, backward-facing: ROTATION_PITCH_180, forward-facing: ROTATION_NONE, left-facing: ROTATION_YAW_90, right-facing: ROTATION_YAW_270 - */ -static inline uint8_t mavlink_msg_distance_sensor_get_orientation(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 12); -} - -/** - * @brief Get field covariance from distance_sensor message - * - * @return [cm^2] Measurement variance. Max standard deviation is 6cm. UINT8_MAX if unknown. - */ -static inline uint8_t mavlink_msg_distance_sensor_get_covariance(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 13); -} - -/** - * @brief Get field horizontal_fov from distance_sensor message - * - * @return [rad] Horizontal Field of View (angle) where the distance measurement is valid and the field of view is known. Otherwise this is set to 0. - */ -static inline float mavlink_msg_distance_sensor_get_horizontal_fov(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 14); -} - -/** - * @brief Get field vertical_fov from distance_sensor message - * - * @return [rad] Vertical Field of View (angle) where the distance measurement is valid and the field of view is known. Otherwise this is set to 0. - */ -static inline float mavlink_msg_distance_sensor_get_vertical_fov(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 18); -} - -/** - * @brief Get field quaternion from distance_sensor message - * - * @return Quaternion of the sensor orientation in vehicle body frame (w, x, y, z order, zero-rotation is 1, 0, 0, 0). Zero-rotation is along the vehicle body x-axis. This field is required if the orientation is set to MAV_SENSOR_ROTATION_CUSTOM. Set it to 0 if invalid." - */ -static inline uint16_t mavlink_msg_distance_sensor_get_quaternion(const mavlink_message_t* msg, float *quaternion) -{ - return _MAV_RETURN_float_array(msg, quaternion, 4, 22); -} - -/** - * @brief Get field signal_quality from distance_sensor message - * - * @return [%] Signal quality of the sensor. Specific to each sensor type, representing the relation of the signal strength with the target reflectivity, distance, size or aspect, but normalised as a percentage. 0 = unknown/unset signal quality, 1 = invalid signal, 100 = perfect signal. - */ -static inline uint8_t mavlink_msg_distance_sensor_get_signal_quality(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 38); -} - -/** - * @brief Decode a distance_sensor message into a struct - * - * @param msg The message to decode - * @param distance_sensor C-struct to decode the message contents into - */ -static inline void mavlink_msg_distance_sensor_decode(const mavlink_message_t* msg, mavlink_distance_sensor_t* distance_sensor) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - distance_sensor->time_boot_ms = mavlink_msg_distance_sensor_get_time_boot_ms(msg); - distance_sensor->min_distance = mavlink_msg_distance_sensor_get_min_distance(msg); - distance_sensor->max_distance = mavlink_msg_distance_sensor_get_max_distance(msg); - distance_sensor->current_distance = mavlink_msg_distance_sensor_get_current_distance(msg); - distance_sensor->type = mavlink_msg_distance_sensor_get_type(msg); - distance_sensor->id = mavlink_msg_distance_sensor_get_id(msg); - distance_sensor->orientation = mavlink_msg_distance_sensor_get_orientation(msg); - distance_sensor->covariance = mavlink_msg_distance_sensor_get_covariance(msg); - distance_sensor->horizontal_fov = mavlink_msg_distance_sensor_get_horizontal_fov(msg); - distance_sensor->vertical_fov = mavlink_msg_distance_sensor_get_vertical_fov(msg); - mavlink_msg_distance_sensor_get_quaternion(msg, distance_sensor->quaternion); - distance_sensor->signal_quality = mavlink_msg_distance_sensor_get_signal_quality(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN? msg->len : MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN; - memset(distance_sensor, 0, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN); - memcpy(distance_sensor, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_efi_status.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_efi_status.h deleted file mode 100644 index 6affcb2b..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_efi_status.h +++ /dev/null @@ -1,663 +0,0 @@ -#pragma once -// MESSAGE EFI_STATUS PACKING - -#define MAVLINK_MSG_ID_EFI_STATUS 225 - -MAVPACKED( -typedef struct __mavlink_efi_status_t { - float ecu_index; /*< ECU index*/ - float rpm; /*< RPM*/ - float fuel_consumed; /*< [cm^3] Fuel consumed*/ - float fuel_flow; /*< [cm^3/min] Fuel flow rate*/ - float engine_load; /*< [%] Engine load*/ - float throttle_position; /*< [%] Throttle position*/ - float spark_dwell_time; /*< [ms] Spark dwell time*/ - float barometric_pressure; /*< [kPa] Barometric pressure*/ - float intake_manifold_pressure; /*< [kPa] Intake manifold pressure(*/ - float intake_manifold_temperature; /*< [degC] Intake manifold temperature*/ - float cylinder_head_temperature; /*< [degC] Cylinder head temperature*/ - float ignition_timing; /*< [deg] Ignition timing (Crank angle degrees)*/ - float injection_time; /*< [ms] Injection time*/ - float exhaust_gas_temperature; /*< [degC] Exhaust gas temperature*/ - float throttle_out; /*< [%] Output throttle*/ - float pt_compensation; /*< Pressure/temperature compensation*/ - uint8_t health; /*< EFI health status*/ - float ignition_voltage; /*< [V] Supply voltage to EFI sparking system. Zero in this value means "unknown", so if the supply voltage really is zero volts use 0.0001 instead.*/ - float fuel_pressure; /*< [kPa] Fuel pressure. Zero in this value means "unknown", so if the fuel pressure really is zero kPa use 0.0001 instead.*/ -}) mavlink_efi_status_t; - -#define MAVLINK_MSG_ID_EFI_STATUS_LEN 73 -#define MAVLINK_MSG_ID_EFI_STATUS_MIN_LEN 65 -#define MAVLINK_MSG_ID_225_LEN 73 -#define MAVLINK_MSG_ID_225_MIN_LEN 65 - -#define MAVLINK_MSG_ID_EFI_STATUS_CRC 208 -#define MAVLINK_MSG_ID_225_CRC 208 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_EFI_STATUS { \ - 225, \ - "EFI_STATUS", \ - 19, \ - { { "health", NULL, MAVLINK_TYPE_UINT8_T, 0, 64, offsetof(mavlink_efi_status_t, health) }, \ - { "ecu_index", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_efi_status_t, ecu_index) }, \ - { "rpm", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_efi_status_t, rpm) }, \ - { "fuel_consumed", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_efi_status_t, fuel_consumed) }, \ - { "fuel_flow", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_efi_status_t, fuel_flow) }, \ - { "engine_load", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_efi_status_t, engine_load) }, \ - { "throttle_position", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_efi_status_t, throttle_position) }, \ - { "spark_dwell_time", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_efi_status_t, spark_dwell_time) }, \ - { "barometric_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_efi_status_t, barometric_pressure) }, \ - { "intake_manifold_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_efi_status_t, intake_manifold_pressure) }, \ - { "intake_manifold_temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_efi_status_t, intake_manifold_temperature) }, \ - { "cylinder_head_temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_efi_status_t, cylinder_head_temperature) }, \ - { "ignition_timing", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_efi_status_t, ignition_timing) }, \ - { "injection_time", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_efi_status_t, injection_time) }, \ - { "exhaust_gas_temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_efi_status_t, exhaust_gas_temperature) }, \ - { "throttle_out", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_efi_status_t, throttle_out) }, \ - { "pt_compensation", NULL, MAVLINK_TYPE_FLOAT, 0, 60, offsetof(mavlink_efi_status_t, pt_compensation) }, \ - { "ignition_voltage", NULL, MAVLINK_TYPE_FLOAT, 0, 65, offsetof(mavlink_efi_status_t, ignition_voltage) }, \ - { "fuel_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 69, offsetof(mavlink_efi_status_t, fuel_pressure) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_EFI_STATUS { \ - "EFI_STATUS", \ - 19, \ - { { "health", NULL, MAVLINK_TYPE_UINT8_T, 0, 64, offsetof(mavlink_efi_status_t, health) }, \ - { "ecu_index", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_efi_status_t, ecu_index) }, \ - { "rpm", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_efi_status_t, rpm) }, \ - { "fuel_consumed", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_efi_status_t, fuel_consumed) }, \ - { "fuel_flow", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_efi_status_t, fuel_flow) }, \ - { "engine_load", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_efi_status_t, engine_load) }, \ - { "throttle_position", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_efi_status_t, throttle_position) }, \ - { "spark_dwell_time", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_efi_status_t, spark_dwell_time) }, \ - { "barometric_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_efi_status_t, barometric_pressure) }, \ - { "intake_manifold_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_efi_status_t, intake_manifold_pressure) }, \ - { "intake_manifold_temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_efi_status_t, intake_manifold_temperature) }, \ - { "cylinder_head_temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_efi_status_t, cylinder_head_temperature) }, \ - { "ignition_timing", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_efi_status_t, ignition_timing) }, \ - { "injection_time", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_efi_status_t, injection_time) }, \ - { "exhaust_gas_temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_efi_status_t, exhaust_gas_temperature) }, \ - { "throttle_out", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_efi_status_t, throttle_out) }, \ - { "pt_compensation", NULL, MAVLINK_TYPE_FLOAT, 0, 60, offsetof(mavlink_efi_status_t, pt_compensation) }, \ - { "ignition_voltage", NULL, MAVLINK_TYPE_FLOAT, 0, 65, offsetof(mavlink_efi_status_t, ignition_voltage) }, \ - { "fuel_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 69, offsetof(mavlink_efi_status_t, fuel_pressure) }, \ - } \ -} -#endif - -/** - * @brief Pack a efi_status message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param health EFI health status - * @param ecu_index ECU index - * @param rpm RPM - * @param fuel_consumed [cm^3] Fuel consumed - * @param fuel_flow [cm^3/min] Fuel flow rate - * @param engine_load [%] Engine load - * @param throttle_position [%] Throttle position - * @param spark_dwell_time [ms] Spark dwell time - * @param barometric_pressure [kPa] Barometric pressure - * @param intake_manifold_pressure [kPa] Intake manifold pressure( - * @param intake_manifold_temperature [degC] Intake manifold temperature - * @param cylinder_head_temperature [degC] Cylinder head temperature - * @param ignition_timing [deg] Ignition timing (Crank angle degrees) - * @param injection_time [ms] Injection time - * @param exhaust_gas_temperature [degC] Exhaust gas temperature - * @param throttle_out [%] Output throttle - * @param pt_compensation Pressure/temperature compensation - * @param ignition_voltage [V] Supply voltage to EFI sparking system. Zero in this value means "unknown", so if the supply voltage really is zero volts use 0.0001 instead. - * @param fuel_pressure [kPa] Fuel pressure. Zero in this value means "unknown", so if the fuel pressure really is zero kPa use 0.0001 instead. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_efi_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t health, float ecu_index, float rpm, float fuel_consumed, float fuel_flow, float engine_load, float throttle_position, float spark_dwell_time, float barometric_pressure, float intake_manifold_pressure, float intake_manifold_temperature, float cylinder_head_temperature, float ignition_timing, float injection_time, float exhaust_gas_temperature, float throttle_out, float pt_compensation, float ignition_voltage, float fuel_pressure) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_EFI_STATUS_LEN]; - _mav_put_float(buf, 0, ecu_index); - _mav_put_float(buf, 4, rpm); - _mav_put_float(buf, 8, fuel_consumed); - _mav_put_float(buf, 12, fuel_flow); - _mav_put_float(buf, 16, engine_load); - _mav_put_float(buf, 20, throttle_position); - _mav_put_float(buf, 24, spark_dwell_time); - _mav_put_float(buf, 28, barometric_pressure); - _mav_put_float(buf, 32, intake_manifold_pressure); - _mav_put_float(buf, 36, intake_manifold_temperature); - _mav_put_float(buf, 40, cylinder_head_temperature); - _mav_put_float(buf, 44, ignition_timing); - _mav_put_float(buf, 48, injection_time); - _mav_put_float(buf, 52, exhaust_gas_temperature); - _mav_put_float(buf, 56, throttle_out); - _mav_put_float(buf, 60, pt_compensation); - _mav_put_uint8_t(buf, 64, health); - _mav_put_float(buf, 65, ignition_voltage); - _mav_put_float(buf, 69, fuel_pressure); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_EFI_STATUS_LEN); -#else - mavlink_efi_status_t packet; - packet.ecu_index = ecu_index; - packet.rpm = rpm; - packet.fuel_consumed = fuel_consumed; - packet.fuel_flow = fuel_flow; - packet.engine_load = engine_load; - packet.throttle_position = throttle_position; - packet.spark_dwell_time = spark_dwell_time; - packet.barometric_pressure = barometric_pressure; - packet.intake_manifold_pressure = intake_manifold_pressure; - packet.intake_manifold_temperature = intake_manifold_temperature; - packet.cylinder_head_temperature = cylinder_head_temperature; - packet.ignition_timing = ignition_timing; - packet.injection_time = injection_time; - packet.exhaust_gas_temperature = exhaust_gas_temperature; - packet.throttle_out = throttle_out; - packet.pt_compensation = pt_compensation; - packet.health = health; - packet.ignition_voltage = ignition_voltage; - packet.fuel_pressure = fuel_pressure; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_EFI_STATUS_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_EFI_STATUS; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_EFI_STATUS_MIN_LEN, MAVLINK_MSG_ID_EFI_STATUS_LEN, MAVLINK_MSG_ID_EFI_STATUS_CRC); -} - -/** - * @brief Pack a efi_status message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param health EFI health status - * @param ecu_index ECU index - * @param rpm RPM - * @param fuel_consumed [cm^3] Fuel consumed - * @param fuel_flow [cm^3/min] Fuel flow rate - * @param engine_load [%] Engine load - * @param throttle_position [%] Throttle position - * @param spark_dwell_time [ms] Spark dwell time - * @param barometric_pressure [kPa] Barometric pressure - * @param intake_manifold_pressure [kPa] Intake manifold pressure( - * @param intake_manifold_temperature [degC] Intake manifold temperature - * @param cylinder_head_temperature [degC] Cylinder head temperature - * @param ignition_timing [deg] Ignition timing (Crank angle degrees) - * @param injection_time [ms] Injection time - * @param exhaust_gas_temperature [degC] Exhaust gas temperature - * @param throttle_out [%] Output throttle - * @param pt_compensation Pressure/temperature compensation - * @param ignition_voltage [V] Supply voltage to EFI sparking system. Zero in this value means "unknown", so if the supply voltage really is zero volts use 0.0001 instead. - * @param fuel_pressure [kPa] Fuel pressure. Zero in this value means "unknown", so if the fuel pressure really is zero kPa use 0.0001 instead. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_efi_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t health,float ecu_index,float rpm,float fuel_consumed,float fuel_flow,float engine_load,float throttle_position,float spark_dwell_time,float barometric_pressure,float intake_manifold_pressure,float intake_manifold_temperature,float cylinder_head_temperature,float ignition_timing,float injection_time,float exhaust_gas_temperature,float throttle_out,float pt_compensation,float ignition_voltage,float fuel_pressure) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_EFI_STATUS_LEN]; - _mav_put_float(buf, 0, ecu_index); - _mav_put_float(buf, 4, rpm); - _mav_put_float(buf, 8, fuel_consumed); - _mav_put_float(buf, 12, fuel_flow); - _mav_put_float(buf, 16, engine_load); - _mav_put_float(buf, 20, throttle_position); - _mav_put_float(buf, 24, spark_dwell_time); - _mav_put_float(buf, 28, barometric_pressure); - _mav_put_float(buf, 32, intake_manifold_pressure); - _mav_put_float(buf, 36, intake_manifold_temperature); - _mav_put_float(buf, 40, cylinder_head_temperature); - _mav_put_float(buf, 44, ignition_timing); - _mav_put_float(buf, 48, injection_time); - _mav_put_float(buf, 52, exhaust_gas_temperature); - _mav_put_float(buf, 56, throttle_out); - _mav_put_float(buf, 60, pt_compensation); - _mav_put_uint8_t(buf, 64, health); - _mav_put_float(buf, 65, ignition_voltage); - _mav_put_float(buf, 69, fuel_pressure); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_EFI_STATUS_LEN); -#else - mavlink_efi_status_t packet; - packet.ecu_index = ecu_index; - packet.rpm = rpm; - packet.fuel_consumed = fuel_consumed; - packet.fuel_flow = fuel_flow; - packet.engine_load = engine_load; - packet.throttle_position = throttle_position; - packet.spark_dwell_time = spark_dwell_time; - packet.barometric_pressure = barometric_pressure; - packet.intake_manifold_pressure = intake_manifold_pressure; - packet.intake_manifold_temperature = intake_manifold_temperature; - packet.cylinder_head_temperature = cylinder_head_temperature; - packet.ignition_timing = ignition_timing; - packet.injection_time = injection_time; - packet.exhaust_gas_temperature = exhaust_gas_temperature; - packet.throttle_out = throttle_out; - packet.pt_compensation = pt_compensation; - packet.health = health; - packet.ignition_voltage = ignition_voltage; - packet.fuel_pressure = fuel_pressure; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_EFI_STATUS_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_EFI_STATUS; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_EFI_STATUS_MIN_LEN, MAVLINK_MSG_ID_EFI_STATUS_LEN, MAVLINK_MSG_ID_EFI_STATUS_CRC); -} - -/** - * @brief Encode a efi_status struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param efi_status C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_efi_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_efi_status_t* efi_status) -{ - return mavlink_msg_efi_status_pack(system_id, component_id, msg, efi_status->health, efi_status->ecu_index, efi_status->rpm, efi_status->fuel_consumed, efi_status->fuel_flow, efi_status->engine_load, efi_status->throttle_position, efi_status->spark_dwell_time, efi_status->barometric_pressure, efi_status->intake_manifold_pressure, efi_status->intake_manifold_temperature, efi_status->cylinder_head_temperature, efi_status->ignition_timing, efi_status->injection_time, efi_status->exhaust_gas_temperature, efi_status->throttle_out, efi_status->pt_compensation, efi_status->ignition_voltage, efi_status->fuel_pressure); -} - -/** - * @brief Encode a efi_status struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param efi_status C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_efi_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_efi_status_t* efi_status) -{ - return mavlink_msg_efi_status_pack_chan(system_id, component_id, chan, msg, efi_status->health, efi_status->ecu_index, efi_status->rpm, efi_status->fuel_consumed, efi_status->fuel_flow, efi_status->engine_load, efi_status->throttle_position, efi_status->spark_dwell_time, efi_status->barometric_pressure, efi_status->intake_manifold_pressure, efi_status->intake_manifold_temperature, efi_status->cylinder_head_temperature, efi_status->ignition_timing, efi_status->injection_time, efi_status->exhaust_gas_temperature, efi_status->throttle_out, efi_status->pt_compensation, efi_status->ignition_voltage, efi_status->fuel_pressure); -} - -/** - * @brief Send a efi_status message - * @param chan MAVLink channel to send the message - * - * @param health EFI health status - * @param ecu_index ECU index - * @param rpm RPM - * @param fuel_consumed [cm^3] Fuel consumed - * @param fuel_flow [cm^3/min] Fuel flow rate - * @param engine_load [%] Engine load - * @param throttle_position [%] Throttle position - * @param spark_dwell_time [ms] Spark dwell time - * @param barometric_pressure [kPa] Barometric pressure - * @param intake_manifold_pressure [kPa] Intake manifold pressure( - * @param intake_manifold_temperature [degC] Intake manifold temperature - * @param cylinder_head_temperature [degC] Cylinder head temperature - * @param ignition_timing [deg] Ignition timing (Crank angle degrees) - * @param injection_time [ms] Injection time - * @param exhaust_gas_temperature [degC] Exhaust gas temperature - * @param throttle_out [%] Output throttle - * @param pt_compensation Pressure/temperature compensation - * @param ignition_voltage [V] Supply voltage to EFI sparking system. Zero in this value means "unknown", so if the supply voltage really is zero volts use 0.0001 instead. - * @param fuel_pressure [kPa] Fuel pressure. Zero in this value means "unknown", so if the fuel pressure really is zero kPa use 0.0001 instead. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_efi_status_send(mavlink_channel_t chan, uint8_t health, float ecu_index, float rpm, float fuel_consumed, float fuel_flow, float engine_load, float throttle_position, float spark_dwell_time, float barometric_pressure, float intake_manifold_pressure, float intake_manifold_temperature, float cylinder_head_temperature, float ignition_timing, float injection_time, float exhaust_gas_temperature, float throttle_out, float pt_compensation, float ignition_voltage, float fuel_pressure) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_EFI_STATUS_LEN]; - _mav_put_float(buf, 0, ecu_index); - _mav_put_float(buf, 4, rpm); - _mav_put_float(buf, 8, fuel_consumed); - _mav_put_float(buf, 12, fuel_flow); - _mav_put_float(buf, 16, engine_load); - _mav_put_float(buf, 20, throttle_position); - _mav_put_float(buf, 24, spark_dwell_time); - _mav_put_float(buf, 28, barometric_pressure); - _mav_put_float(buf, 32, intake_manifold_pressure); - _mav_put_float(buf, 36, intake_manifold_temperature); - _mav_put_float(buf, 40, cylinder_head_temperature); - _mav_put_float(buf, 44, ignition_timing); - _mav_put_float(buf, 48, injection_time); - _mav_put_float(buf, 52, exhaust_gas_temperature); - _mav_put_float(buf, 56, throttle_out); - _mav_put_float(buf, 60, pt_compensation); - _mav_put_uint8_t(buf, 64, health); - _mav_put_float(buf, 65, ignition_voltage); - _mav_put_float(buf, 69, fuel_pressure); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_EFI_STATUS, buf, MAVLINK_MSG_ID_EFI_STATUS_MIN_LEN, MAVLINK_MSG_ID_EFI_STATUS_LEN, MAVLINK_MSG_ID_EFI_STATUS_CRC); -#else - mavlink_efi_status_t packet; - packet.ecu_index = ecu_index; - packet.rpm = rpm; - packet.fuel_consumed = fuel_consumed; - packet.fuel_flow = fuel_flow; - packet.engine_load = engine_load; - packet.throttle_position = throttle_position; - packet.spark_dwell_time = spark_dwell_time; - packet.barometric_pressure = barometric_pressure; - packet.intake_manifold_pressure = intake_manifold_pressure; - packet.intake_manifold_temperature = intake_manifold_temperature; - packet.cylinder_head_temperature = cylinder_head_temperature; - packet.ignition_timing = ignition_timing; - packet.injection_time = injection_time; - packet.exhaust_gas_temperature = exhaust_gas_temperature; - packet.throttle_out = throttle_out; - packet.pt_compensation = pt_compensation; - packet.health = health; - packet.ignition_voltage = ignition_voltage; - packet.fuel_pressure = fuel_pressure; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_EFI_STATUS, (const char *)&packet, MAVLINK_MSG_ID_EFI_STATUS_MIN_LEN, MAVLINK_MSG_ID_EFI_STATUS_LEN, MAVLINK_MSG_ID_EFI_STATUS_CRC); -#endif -} - -/** - * @brief Send a efi_status message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_efi_status_send_struct(mavlink_channel_t chan, const mavlink_efi_status_t* efi_status) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_efi_status_send(chan, efi_status->health, efi_status->ecu_index, efi_status->rpm, efi_status->fuel_consumed, efi_status->fuel_flow, efi_status->engine_load, efi_status->throttle_position, efi_status->spark_dwell_time, efi_status->barometric_pressure, efi_status->intake_manifold_pressure, efi_status->intake_manifold_temperature, efi_status->cylinder_head_temperature, efi_status->ignition_timing, efi_status->injection_time, efi_status->exhaust_gas_temperature, efi_status->throttle_out, efi_status->pt_compensation, efi_status->ignition_voltage, efi_status->fuel_pressure); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_EFI_STATUS, (const char *)efi_status, MAVLINK_MSG_ID_EFI_STATUS_MIN_LEN, MAVLINK_MSG_ID_EFI_STATUS_LEN, MAVLINK_MSG_ID_EFI_STATUS_CRC); -#endif -} - -#if MAVLINK_MSG_ID_EFI_STATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_efi_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t health, float ecu_index, float rpm, float fuel_consumed, float fuel_flow, float engine_load, float throttle_position, float spark_dwell_time, float barometric_pressure, float intake_manifold_pressure, float intake_manifold_temperature, float cylinder_head_temperature, float ignition_timing, float injection_time, float exhaust_gas_temperature, float throttle_out, float pt_compensation, float ignition_voltage, float fuel_pressure) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_float(buf, 0, ecu_index); - _mav_put_float(buf, 4, rpm); - _mav_put_float(buf, 8, fuel_consumed); - _mav_put_float(buf, 12, fuel_flow); - _mav_put_float(buf, 16, engine_load); - _mav_put_float(buf, 20, throttle_position); - _mav_put_float(buf, 24, spark_dwell_time); - _mav_put_float(buf, 28, barometric_pressure); - _mav_put_float(buf, 32, intake_manifold_pressure); - _mav_put_float(buf, 36, intake_manifold_temperature); - _mav_put_float(buf, 40, cylinder_head_temperature); - _mav_put_float(buf, 44, ignition_timing); - _mav_put_float(buf, 48, injection_time); - _mav_put_float(buf, 52, exhaust_gas_temperature); - _mav_put_float(buf, 56, throttle_out); - _mav_put_float(buf, 60, pt_compensation); - _mav_put_uint8_t(buf, 64, health); - _mav_put_float(buf, 65, ignition_voltage); - _mav_put_float(buf, 69, fuel_pressure); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_EFI_STATUS, buf, MAVLINK_MSG_ID_EFI_STATUS_MIN_LEN, MAVLINK_MSG_ID_EFI_STATUS_LEN, MAVLINK_MSG_ID_EFI_STATUS_CRC); -#else - mavlink_efi_status_t *packet = (mavlink_efi_status_t *)msgbuf; - packet->ecu_index = ecu_index; - packet->rpm = rpm; - packet->fuel_consumed = fuel_consumed; - packet->fuel_flow = fuel_flow; - packet->engine_load = engine_load; - packet->throttle_position = throttle_position; - packet->spark_dwell_time = spark_dwell_time; - packet->barometric_pressure = barometric_pressure; - packet->intake_manifold_pressure = intake_manifold_pressure; - packet->intake_manifold_temperature = intake_manifold_temperature; - packet->cylinder_head_temperature = cylinder_head_temperature; - packet->ignition_timing = ignition_timing; - packet->injection_time = injection_time; - packet->exhaust_gas_temperature = exhaust_gas_temperature; - packet->throttle_out = throttle_out; - packet->pt_compensation = pt_compensation; - packet->health = health; - packet->ignition_voltage = ignition_voltage; - packet->fuel_pressure = fuel_pressure; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_EFI_STATUS, (const char *)packet, MAVLINK_MSG_ID_EFI_STATUS_MIN_LEN, MAVLINK_MSG_ID_EFI_STATUS_LEN, MAVLINK_MSG_ID_EFI_STATUS_CRC); -#endif -} -#endif - -#endif - -// MESSAGE EFI_STATUS UNPACKING - - -/** - * @brief Get field health from efi_status message - * - * @return EFI health status - */ -static inline uint8_t mavlink_msg_efi_status_get_health(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 64); -} - -/** - * @brief Get field ecu_index from efi_status message - * - * @return ECU index - */ -static inline float mavlink_msg_efi_status_get_ecu_index(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 0); -} - -/** - * @brief Get field rpm from efi_status message - * - * @return RPM - */ -static inline float mavlink_msg_efi_status_get_rpm(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 4); -} - -/** - * @brief Get field fuel_consumed from efi_status message - * - * @return [cm^3] Fuel consumed - */ -static inline float mavlink_msg_efi_status_get_fuel_consumed(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field fuel_flow from efi_status message - * - * @return [cm^3/min] Fuel flow rate - */ -static inline float mavlink_msg_efi_status_get_fuel_flow(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field engine_load from efi_status message - * - * @return [%] Engine load - */ -static inline float mavlink_msg_efi_status_get_engine_load(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field throttle_position from efi_status message - * - * @return [%] Throttle position - */ -static inline float mavlink_msg_efi_status_get_throttle_position(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Get field spark_dwell_time from efi_status message - * - * @return [ms] Spark dwell time - */ -static inline float mavlink_msg_efi_status_get_spark_dwell_time(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Get field barometric_pressure from efi_status message - * - * @return [kPa] Barometric pressure - */ -static inline float mavlink_msg_efi_status_get_barometric_pressure(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 28); -} - -/** - * @brief Get field intake_manifold_pressure from efi_status message - * - * @return [kPa] Intake manifold pressure( - */ -static inline float mavlink_msg_efi_status_get_intake_manifold_pressure(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 32); -} - -/** - * @brief Get field intake_manifold_temperature from efi_status message - * - * @return [degC] Intake manifold temperature - */ -static inline float mavlink_msg_efi_status_get_intake_manifold_temperature(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 36); -} - -/** - * @brief Get field cylinder_head_temperature from efi_status message - * - * @return [degC] Cylinder head temperature - */ -static inline float mavlink_msg_efi_status_get_cylinder_head_temperature(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 40); -} - -/** - * @brief Get field ignition_timing from efi_status message - * - * @return [deg] Ignition timing (Crank angle degrees) - */ -static inline float mavlink_msg_efi_status_get_ignition_timing(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 44); -} - -/** - * @brief Get field injection_time from efi_status message - * - * @return [ms] Injection time - */ -static inline float mavlink_msg_efi_status_get_injection_time(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 48); -} - -/** - * @brief Get field exhaust_gas_temperature from efi_status message - * - * @return [degC] Exhaust gas temperature - */ -static inline float mavlink_msg_efi_status_get_exhaust_gas_temperature(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 52); -} - -/** - * @brief Get field throttle_out from efi_status message - * - * @return [%] Output throttle - */ -static inline float mavlink_msg_efi_status_get_throttle_out(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 56); -} - -/** - * @brief Get field pt_compensation from efi_status message - * - * @return Pressure/temperature compensation - */ -static inline float mavlink_msg_efi_status_get_pt_compensation(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 60); -} - -/** - * @brief Get field ignition_voltage from efi_status message - * - * @return [V] Supply voltage to EFI sparking system. Zero in this value means "unknown", so if the supply voltage really is zero volts use 0.0001 instead. - */ -static inline float mavlink_msg_efi_status_get_ignition_voltage(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 65); -} - -/** - * @brief Get field fuel_pressure from efi_status message - * - * @return [kPa] Fuel pressure. Zero in this value means "unknown", so if the fuel pressure really is zero kPa use 0.0001 instead. - */ -static inline float mavlink_msg_efi_status_get_fuel_pressure(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 69); -} - -/** - * @brief Decode a efi_status message into a struct - * - * @param msg The message to decode - * @param efi_status C-struct to decode the message contents into - */ -static inline void mavlink_msg_efi_status_decode(const mavlink_message_t* msg, mavlink_efi_status_t* efi_status) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - efi_status->ecu_index = mavlink_msg_efi_status_get_ecu_index(msg); - efi_status->rpm = mavlink_msg_efi_status_get_rpm(msg); - efi_status->fuel_consumed = mavlink_msg_efi_status_get_fuel_consumed(msg); - efi_status->fuel_flow = mavlink_msg_efi_status_get_fuel_flow(msg); - efi_status->engine_load = mavlink_msg_efi_status_get_engine_load(msg); - efi_status->throttle_position = mavlink_msg_efi_status_get_throttle_position(msg); - efi_status->spark_dwell_time = mavlink_msg_efi_status_get_spark_dwell_time(msg); - efi_status->barometric_pressure = mavlink_msg_efi_status_get_barometric_pressure(msg); - efi_status->intake_manifold_pressure = mavlink_msg_efi_status_get_intake_manifold_pressure(msg); - efi_status->intake_manifold_temperature = mavlink_msg_efi_status_get_intake_manifold_temperature(msg); - efi_status->cylinder_head_temperature = mavlink_msg_efi_status_get_cylinder_head_temperature(msg); - efi_status->ignition_timing = mavlink_msg_efi_status_get_ignition_timing(msg); - efi_status->injection_time = mavlink_msg_efi_status_get_injection_time(msg); - efi_status->exhaust_gas_temperature = mavlink_msg_efi_status_get_exhaust_gas_temperature(msg); - efi_status->throttle_out = mavlink_msg_efi_status_get_throttle_out(msg); - efi_status->pt_compensation = mavlink_msg_efi_status_get_pt_compensation(msg); - efi_status->health = mavlink_msg_efi_status_get_health(msg); - efi_status->ignition_voltage = mavlink_msg_efi_status_get_ignition_voltage(msg); - efi_status->fuel_pressure = mavlink_msg_efi_status_get_fuel_pressure(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_EFI_STATUS_LEN? msg->len : MAVLINK_MSG_ID_EFI_STATUS_LEN; - memset(efi_status, 0, MAVLINK_MSG_ID_EFI_STATUS_LEN); - memcpy(efi_status, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_encapsulated_data.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_encapsulated_data.h deleted file mode 100644 index 5f69c898..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_encapsulated_data.h +++ /dev/null @@ -1,230 +0,0 @@ -#pragma once -// MESSAGE ENCAPSULATED_DATA PACKING - -#define MAVLINK_MSG_ID_ENCAPSULATED_DATA 131 - - -typedef struct __mavlink_encapsulated_data_t { - uint16_t seqnr; /*< sequence number (starting with 0 on every transmission)*/ - uint8_t data[253]; /*< image data bytes*/ -} mavlink_encapsulated_data_t; - -#define MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN 255 -#define MAVLINK_MSG_ID_ENCAPSULATED_DATA_MIN_LEN 255 -#define MAVLINK_MSG_ID_131_LEN 255 -#define MAVLINK_MSG_ID_131_MIN_LEN 255 - -#define MAVLINK_MSG_ID_ENCAPSULATED_DATA_CRC 223 -#define MAVLINK_MSG_ID_131_CRC 223 - -#define MAVLINK_MSG_ENCAPSULATED_DATA_FIELD_DATA_LEN 253 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_ENCAPSULATED_DATA { \ - 131, \ - "ENCAPSULATED_DATA", \ - 2, \ - { { "seqnr", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_encapsulated_data_t, seqnr) }, \ - { "data", NULL, MAVLINK_TYPE_UINT8_T, 253, 2, offsetof(mavlink_encapsulated_data_t, data) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_ENCAPSULATED_DATA { \ - "ENCAPSULATED_DATA", \ - 2, \ - { { "seqnr", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_encapsulated_data_t, seqnr) }, \ - { "data", NULL, MAVLINK_TYPE_UINT8_T, 253, 2, offsetof(mavlink_encapsulated_data_t, data) }, \ - } \ -} -#endif - -/** - * @brief Pack a encapsulated_data message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param seqnr sequence number (starting with 0 on every transmission) - * @param data image data bytes - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_encapsulated_data_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint16_t seqnr, const uint8_t *data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN]; - _mav_put_uint16_t(buf, 0, seqnr); - _mav_put_uint8_t_array(buf, 2, data, 253); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN); -#else - mavlink_encapsulated_data_t packet; - packet.seqnr = seqnr; - mav_array_memcpy(packet.data, data, sizeof(uint8_t)*253); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_ENCAPSULATED_DATA; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ENCAPSULATED_DATA_MIN_LEN, MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN, MAVLINK_MSG_ID_ENCAPSULATED_DATA_CRC); -} - -/** - * @brief Pack a encapsulated_data message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param seqnr sequence number (starting with 0 on every transmission) - * @param data image data bytes - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_encapsulated_data_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint16_t seqnr,const uint8_t *data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN]; - _mav_put_uint16_t(buf, 0, seqnr); - _mav_put_uint8_t_array(buf, 2, data, 253); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN); -#else - mavlink_encapsulated_data_t packet; - packet.seqnr = seqnr; - mav_array_memcpy(packet.data, data, sizeof(uint8_t)*253); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_ENCAPSULATED_DATA; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ENCAPSULATED_DATA_MIN_LEN, MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN, MAVLINK_MSG_ID_ENCAPSULATED_DATA_CRC); -} - -/** - * @brief Encode a encapsulated_data struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param encapsulated_data C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_encapsulated_data_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_encapsulated_data_t* encapsulated_data) -{ - return mavlink_msg_encapsulated_data_pack(system_id, component_id, msg, encapsulated_data->seqnr, encapsulated_data->data); -} - -/** - * @brief Encode a encapsulated_data struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param encapsulated_data C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_encapsulated_data_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_encapsulated_data_t* encapsulated_data) -{ - return mavlink_msg_encapsulated_data_pack_chan(system_id, component_id, chan, msg, encapsulated_data->seqnr, encapsulated_data->data); -} - -/** - * @brief Send a encapsulated_data message - * @param chan MAVLink channel to send the message - * - * @param seqnr sequence number (starting with 0 on every transmission) - * @param data image data bytes - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_encapsulated_data_send(mavlink_channel_t chan, uint16_t seqnr, const uint8_t *data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN]; - _mav_put_uint16_t(buf, 0, seqnr); - _mav_put_uint8_t_array(buf, 2, data, 253); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ENCAPSULATED_DATA, buf, MAVLINK_MSG_ID_ENCAPSULATED_DATA_MIN_LEN, MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN, MAVLINK_MSG_ID_ENCAPSULATED_DATA_CRC); -#else - mavlink_encapsulated_data_t packet; - packet.seqnr = seqnr; - mav_array_memcpy(packet.data, data, sizeof(uint8_t)*253); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ENCAPSULATED_DATA, (const char *)&packet, MAVLINK_MSG_ID_ENCAPSULATED_DATA_MIN_LEN, MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN, MAVLINK_MSG_ID_ENCAPSULATED_DATA_CRC); -#endif -} - -/** - * @brief Send a encapsulated_data message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_encapsulated_data_send_struct(mavlink_channel_t chan, const mavlink_encapsulated_data_t* encapsulated_data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_encapsulated_data_send(chan, encapsulated_data->seqnr, encapsulated_data->data); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ENCAPSULATED_DATA, (const char *)encapsulated_data, MAVLINK_MSG_ID_ENCAPSULATED_DATA_MIN_LEN, MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN, MAVLINK_MSG_ID_ENCAPSULATED_DATA_CRC); -#endif -} - -#if MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_encapsulated_data_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint16_t seqnr, const uint8_t *data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint16_t(buf, 0, seqnr); - _mav_put_uint8_t_array(buf, 2, data, 253); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ENCAPSULATED_DATA, buf, MAVLINK_MSG_ID_ENCAPSULATED_DATA_MIN_LEN, MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN, MAVLINK_MSG_ID_ENCAPSULATED_DATA_CRC); -#else - mavlink_encapsulated_data_t *packet = (mavlink_encapsulated_data_t *)msgbuf; - packet->seqnr = seqnr; - mav_array_memcpy(packet->data, data, sizeof(uint8_t)*253); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ENCAPSULATED_DATA, (const char *)packet, MAVLINK_MSG_ID_ENCAPSULATED_DATA_MIN_LEN, MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN, MAVLINK_MSG_ID_ENCAPSULATED_DATA_CRC); -#endif -} -#endif - -#endif - -// MESSAGE ENCAPSULATED_DATA UNPACKING - - -/** - * @brief Get field seqnr from encapsulated_data message - * - * @return sequence number (starting with 0 on every transmission) - */ -static inline uint16_t mavlink_msg_encapsulated_data_get_seqnr(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 0); -} - -/** - * @brief Get field data from encapsulated_data message - * - * @return image data bytes - */ -static inline uint16_t mavlink_msg_encapsulated_data_get_data(const mavlink_message_t* msg, uint8_t *data) -{ - return _MAV_RETURN_uint8_t_array(msg, data, 253, 2); -} - -/** - * @brief Decode a encapsulated_data message into a struct - * - * @param msg The message to decode - * @param encapsulated_data C-struct to decode the message contents into - */ -static inline void mavlink_msg_encapsulated_data_decode(const mavlink_message_t* msg, mavlink_encapsulated_data_t* encapsulated_data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - encapsulated_data->seqnr = mavlink_msg_encapsulated_data_get_seqnr(msg); - mavlink_msg_encapsulated_data_get_data(msg, encapsulated_data->data); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN? msg->len : MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN; - memset(encapsulated_data, 0, MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN); - memcpy(encapsulated_data, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_esc_info.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_esc_info.h deleted file mode 100644 index ba1f2eb0..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_esc_info.h +++ /dev/null @@ -1,407 +0,0 @@ -#pragma once -// MESSAGE ESC_INFO PACKING - -#define MAVLINK_MSG_ID_ESC_INFO 290 - - -typedef struct __mavlink_esc_info_t { - uint64_t time_usec; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude the number.*/ - uint32_t error_count[4]; /*< Number of reported errors by each ESC since boot.*/ - uint16_t counter; /*< Counter of data packets received.*/ - uint16_t failure_flags[4]; /*< Bitmap of ESC failure flags.*/ - int16_t temperature[4]; /*< [cdegC] Temperature of each ESC. INT16_MAX: if data not supplied by ESC.*/ - uint8_t index; /*< Index of the first ESC in this message. minValue = 0, maxValue = 60, increment = 4.*/ - uint8_t count; /*< Total number of ESCs in all messages of this type. Message fields with an index higher than this should be ignored because they contain invalid data.*/ - uint8_t connection_type; /*< Connection type protocol for all ESC.*/ - uint8_t info; /*< Information regarding online/offline status of each ESC.*/ -} mavlink_esc_info_t; - -#define MAVLINK_MSG_ID_ESC_INFO_LEN 46 -#define MAVLINK_MSG_ID_ESC_INFO_MIN_LEN 46 -#define MAVLINK_MSG_ID_290_LEN 46 -#define MAVLINK_MSG_ID_290_MIN_LEN 46 - -#define MAVLINK_MSG_ID_ESC_INFO_CRC 251 -#define MAVLINK_MSG_ID_290_CRC 251 - -#define MAVLINK_MSG_ESC_INFO_FIELD_ERROR_COUNT_LEN 4 -#define MAVLINK_MSG_ESC_INFO_FIELD_FAILURE_FLAGS_LEN 4 -#define MAVLINK_MSG_ESC_INFO_FIELD_TEMPERATURE_LEN 4 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_ESC_INFO { \ - 290, \ - "ESC_INFO", \ - 9, \ - { { "index", NULL, MAVLINK_TYPE_UINT8_T, 0, 42, offsetof(mavlink_esc_info_t, index) }, \ - { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_esc_info_t, time_usec) }, \ - { "counter", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_esc_info_t, counter) }, \ - { "count", NULL, MAVLINK_TYPE_UINT8_T, 0, 43, offsetof(mavlink_esc_info_t, count) }, \ - { "connection_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 44, offsetof(mavlink_esc_info_t, connection_type) }, \ - { "info", NULL, MAVLINK_TYPE_UINT8_T, 0, 45, offsetof(mavlink_esc_info_t, info) }, \ - { "failure_flags", NULL, MAVLINK_TYPE_UINT16_T, 4, 26, offsetof(mavlink_esc_info_t, failure_flags) }, \ - { "error_count", NULL, MAVLINK_TYPE_UINT32_T, 4, 8, offsetof(mavlink_esc_info_t, error_count) }, \ - { "temperature", NULL, MAVLINK_TYPE_INT16_T, 4, 34, offsetof(mavlink_esc_info_t, temperature) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_ESC_INFO { \ - "ESC_INFO", \ - 9, \ - { { "index", NULL, MAVLINK_TYPE_UINT8_T, 0, 42, offsetof(mavlink_esc_info_t, index) }, \ - { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_esc_info_t, time_usec) }, \ - { "counter", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_esc_info_t, counter) }, \ - { "count", NULL, MAVLINK_TYPE_UINT8_T, 0, 43, offsetof(mavlink_esc_info_t, count) }, \ - { "connection_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 44, offsetof(mavlink_esc_info_t, connection_type) }, \ - { "info", NULL, MAVLINK_TYPE_UINT8_T, 0, 45, offsetof(mavlink_esc_info_t, info) }, \ - { "failure_flags", NULL, MAVLINK_TYPE_UINT16_T, 4, 26, offsetof(mavlink_esc_info_t, failure_flags) }, \ - { "error_count", NULL, MAVLINK_TYPE_UINT32_T, 4, 8, offsetof(mavlink_esc_info_t, error_count) }, \ - { "temperature", NULL, MAVLINK_TYPE_INT16_T, 4, 34, offsetof(mavlink_esc_info_t, temperature) }, \ - } \ -} -#endif - -/** - * @brief Pack a esc_info message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param index Index of the first ESC in this message. minValue = 0, maxValue = 60, increment = 4. - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude the number. - * @param counter Counter of data packets received. - * @param count Total number of ESCs in all messages of this type. Message fields with an index higher than this should be ignored because they contain invalid data. - * @param connection_type Connection type protocol for all ESC. - * @param info Information regarding online/offline status of each ESC. - * @param failure_flags Bitmap of ESC failure flags. - * @param error_count Number of reported errors by each ESC since boot. - * @param temperature [cdegC] Temperature of each ESC. INT16_MAX: if data not supplied by ESC. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_esc_info_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t index, uint64_t time_usec, uint16_t counter, uint8_t count, uint8_t connection_type, uint8_t info, const uint16_t *failure_flags, const uint32_t *error_count, const int16_t *temperature) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_ESC_INFO_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint16_t(buf, 24, counter); - _mav_put_uint8_t(buf, 42, index); - _mav_put_uint8_t(buf, 43, count); - _mav_put_uint8_t(buf, 44, connection_type); - _mav_put_uint8_t(buf, 45, info); - _mav_put_uint32_t_array(buf, 8, error_count, 4); - _mav_put_uint16_t_array(buf, 26, failure_flags, 4); - _mav_put_int16_t_array(buf, 34, temperature, 4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ESC_INFO_LEN); -#else - mavlink_esc_info_t packet; - packet.time_usec = time_usec; - packet.counter = counter; - packet.index = index; - packet.count = count; - packet.connection_type = connection_type; - packet.info = info; - mav_array_memcpy(packet.error_count, error_count, sizeof(uint32_t)*4); - mav_array_memcpy(packet.failure_flags, failure_flags, sizeof(uint16_t)*4); - mav_array_memcpy(packet.temperature, temperature, sizeof(int16_t)*4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ESC_INFO_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_ESC_INFO; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ESC_INFO_MIN_LEN, MAVLINK_MSG_ID_ESC_INFO_LEN, MAVLINK_MSG_ID_ESC_INFO_CRC); -} - -/** - * @brief Pack a esc_info message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param index Index of the first ESC in this message. minValue = 0, maxValue = 60, increment = 4. - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude the number. - * @param counter Counter of data packets received. - * @param count Total number of ESCs in all messages of this type. Message fields with an index higher than this should be ignored because they contain invalid data. - * @param connection_type Connection type protocol for all ESC. - * @param info Information regarding online/offline status of each ESC. - * @param failure_flags Bitmap of ESC failure flags. - * @param error_count Number of reported errors by each ESC since boot. - * @param temperature [cdegC] Temperature of each ESC. INT16_MAX: if data not supplied by ESC. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_esc_info_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t index,uint64_t time_usec,uint16_t counter,uint8_t count,uint8_t connection_type,uint8_t info,const uint16_t *failure_flags,const uint32_t *error_count,const int16_t *temperature) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_ESC_INFO_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint16_t(buf, 24, counter); - _mav_put_uint8_t(buf, 42, index); - _mav_put_uint8_t(buf, 43, count); - _mav_put_uint8_t(buf, 44, connection_type); - _mav_put_uint8_t(buf, 45, info); - _mav_put_uint32_t_array(buf, 8, error_count, 4); - _mav_put_uint16_t_array(buf, 26, failure_flags, 4); - _mav_put_int16_t_array(buf, 34, temperature, 4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ESC_INFO_LEN); -#else - mavlink_esc_info_t packet; - packet.time_usec = time_usec; - packet.counter = counter; - packet.index = index; - packet.count = count; - packet.connection_type = connection_type; - packet.info = info; - mav_array_memcpy(packet.error_count, error_count, sizeof(uint32_t)*4); - mav_array_memcpy(packet.failure_flags, failure_flags, sizeof(uint16_t)*4); - mav_array_memcpy(packet.temperature, temperature, sizeof(int16_t)*4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ESC_INFO_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_ESC_INFO; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ESC_INFO_MIN_LEN, MAVLINK_MSG_ID_ESC_INFO_LEN, MAVLINK_MSG_ID_ESC_INFO_CRC); -} - -/** - * @brief Encode a esc_info struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param esc_info C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_esc_info_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_esc_info_t* esc_info) -{ - return mavlink_msg_esc_info_pack(system_id, component_id, msg, esc_info->index, esc_info->time_usec, esc_info->counter, esc_info->count, esc_info->connection_type, esc_info->info, esc_info->failure_flags, esc_info->error_count, esc_info->temperature); -} - -/** - * @brief Encode a esc_info struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param esc_info C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_esc_info_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_esc_info_t* esc_info) -{ - return mavlink_msg_esc_info_pack_chan(system_id, component_id, chan, msg, esc_info->index, esc_info->time_usec, esc_info->counter, esc_info->count, esc_info->connection_type, esc_info->info, esc_info->failure_flags, esc_info->error_count, esc_info->temperature); -} - -/** - * @brief Send a esc_info message - * @param chan MAVLink channel to send the message - * - * @param index Index of the first ESC in this message. minValue = 0, maxValue = 60, increment = 4. - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude the number. - * @param counter Counter of data packets received. - * @param count Total number of ESCs in all messages of this type. Message fields with an index higher than this should be ignored because they contain invalid data. - * @param connection_type Connection type protocol for all ESC. - * @param info Information regarding online/offline status of each ESC. - * @param failure_flags Bitmap of ESC failure flags. - * @param error_count Number of reported errors by each ESC since boot. - * @param temperature [cdegC] Temperature of each ESC. INT16_MAX: if data not supplied by ESC. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_esc_info_send(mavlink_channel_t chan, uint8_t index, uint64_t time_usec, uint16_t counter, uint8_t count, uint8_t connection_type, uint8_t info, const uint16_t *failure_flags, const uint32_t *error_count, const int16_t *temperature) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_ESC_INFO_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint16_t(buf, 24, counter); - _mav_put_uint8_t(buf, 42, index); - _mav_put_uint8_t(buf, 43, count); - _mav_put_uint8_t(buf, 44, connection_type); - _mav_put_uint8_t(buf, 45, info); - _mav_put_uint32_t_array(buf, 8, error_count, 4); - _mav_put_uint16_t_array(buf, 26, failure_flags, 4); - _mav_put_int16_t_array(buf, 34, temperature, 4); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ESC_INFO, buf, MAVLINK_MSG_ID_ESC_INFO_MIN_LEN, MAVLINK_MSG_ID_ESC_INFO_LEN, MAVLINK_MSG_ID_ESC_INFO_CRC); -#else - mavlink_esc_info_t packet; - packet.time_usec = time_usec; - packet.counter = counter; - packet.index = index; - packet.count = count; - packet.connection_type = connection_type; - packet.info = info; - mav_array_memcpy(packet.error_count, error_count, sizeof(uint32_t)*4); - mav_array_memcpy(packet.failure_flags, failure_flags, sizeof(uint16_t)*4); - mav_array_memcpy(packet.temperature, temperature, sizeof(int16_t)*4); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ESC_INFO, (const char *)&packet, MAVLINK_MSG_ID_ESC_INFO_MIN_LEN, MAVLINK_MSG_ID_ESC_INFO_LEN, MAVLINK_MSG_ID_ESC_INFO_CRC); -#endif -} - -/** - * @brief Send a esc_info message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_esc_info_send_struct(mavlink_channel_t chan, const mavlink_esc_info_t* esc_info) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_esc_info_send(chan, esc_info->index, esc_info->time_usec, esc_info->counter, esc_info->count, esc_info->connection_type, esc_info->info, esc_info->failure_flags, esc_info->error_count, esc_info->temperature); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ESC_INFO, (const char *)esc_info, MAVLINK_MSG_ID_ESC_INFO_MIN_LEN, MAVLINK_MSG_ID_ESC_INFO_LEN, MAVLINK_MSG_ID_ESC_INFO_CRC); -#endif -} - -#if MAVLINK_MSG_ID_ESC_INFO_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_esc_info_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t index, uint64_t time_usec, uint16_t counter, uint8_t count, uint8_t connection_type, uint8_t info, const uint16_t *failure_flags, const uint32_t *error_count, const int16_t *temperature) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint16_t(buf, 24, counter); - _mav_put_uint8_t(buf, 42, index); - _mav_put_uint8_t(buf, 43, count); - _mav_put_uint8_t(buf, 44, connection_type); - _mav_put_uint8_t(buf, 45, info); - _mav_put_uint32_t_array(buf, 8, error_count, 4); - _mav_put_uint16_t_array(buf, 26, failure_flags, 4); - _mav_put_int16_t_array(buf, 34, temperature, 4); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ESC_INFO, buf, MAVLINK_MSG_ID_ESC_INFO_MIN_LEN, MAVLINK_MSG_ID_ESC_INFO_LEN, MAVLINK_MSG_ID_ESC_INFO_CRC); -#else - mavlink_esc_info_t *packet = (mavlink_esc_info_t *)msgbuf; - packet->time_usec = time_usec; - packet->counter = counter; - packet->index = index; - packet->count = count; - packet->connection_type = connection_type; - packet->info = info; - mav_array_memcpy(packet->error_count, error_count, sizeof(uint32_t)*4); - mav_array_memcpy(packet->failure_flags, failure_flags, sizeof(uint16_t)*4); - mav_array_memcpy(packet->temperature, temperature, sizeof(int16_t)*4); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ESC_INFO, (const char *)packet, MAVLINK_MSG_ID_ESC_INFO_MIN_LEN, MAVLINK_MSG_ID_ESC_INFO_LEN, MAVLINK_MSG_ID_ESC_INFO_CRC); -#endif -} -#endif - -#endif - -// MESSAGE ESC_INFO UNPACKING - - -/** - * @brief Get field index from esc_info message - * - * @return Index of the first ESC in this message. minValue = 0, maxValue = 60, increment = 4. - */ -static inline uint8_t mavlink_msg_esc_info_get_index(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 42); -} - -/** - * @brief Get field time_usec from esc_info message - * - * @return [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude the number. - */ -static inline uint64_t mavlink_msg_esc_info_get_time_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field counter from esc_info message - * - * @return Counter of data packets received. - */ -static inline uint16_t mavlink_msg_esc_info_get_counter(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 24); -} - -/** - * @brief Get field count from esc_info message - * - * @return Total number of ESCs in all messages of this type. Message fields with an index higher than this should be ignored because they contain invalid data. - */ -static inline uint8_t mavlink_msg_esc_info_get_count(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 43); -} - -/** - * @brief Get field connection_type from esc_info message - * - * @return Connection type protocol for all ESC. - */ -static inline uint8_t mavlink_msg_esc_info_get_connection_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 44); -} - -/** - * @brief Get field info from esc_info message - * - * @return Information regarding online/offline status of each ESC. - */ -static inline uint8_t mavlink_msg_esc_info_get_info(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 45); -} - -/** - * @brief Get field failure_flags from esc_info message - * - * @return Bitmap of ESC failure flags. - */ -static inline uint16_t mavlink_msg_esc_info_get_failure_flags(const mavlink_message_t* msg, uint16_t *failure_flags) -{ - return _MAV_RETURN_uint16_t_array(msg, failure_flags, 4, 26); -} - -/** - * @brief Get field error_count from esc_info message - * - * @return Number of reported errors by each ESC since boot. - */ -static inline uint16_t mavlink_msg_esc_info_get_error_count(const mavlink_message_t* msg, uint32_t *error_count) -{ - return _MAV_RETURN_uint32_t_array(msg, error_count, 4, 8); -} - -/** - * @brief Get field temperature from esc_info message - * - * @return [cdegC] Temperature of each ESC. INT16_MAX: if data not supplied by ESC. - */ -static inline uint16_t mavlink_msg_esc_info_get_temperature(const mavlink_message_t* msg, int16_t *temperature) -{ - return _MAV_RETURN_int16_t_array(msg, temperature, 4, 34); -} - -/** - * @brief Decode a esc_info message into a struct - * - * @param msg The message to decode - * @param esc_info C-struct to decode the message contents into - */ -static inline void mavlink_msg_esc_info_decode(const mavlink_message_t* msg, mavlink_esc_info_t* esc_info) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - esc_info->time_usec = mavlink_msg_esc_info_get_time_usec(msg); - mavlink_msg_esc_info_get_error_count(msg, esc_info->error_count); - esc_info->counter = mavlink_msg_esc_info_get_counter(msg); - mavlink_msg_esc_info_get_failure_flags(msg, esc_info->failure_flags); - mavlink_msg_esc_info_get_temperature(msg, esc_info->temperature); - esc_info->index = mavlink_msg_esc_info_get_index(msg); - esc_info->count = mavlink_msg_esc_info_get_count(msg); - esc_info->connection_type = mavlink_msg_esc_info_get_connection_type(msg); - esc_info->info = mavlink_msg_esc_info_get_info(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_ESC_INFO_LEN? msg->len : MAVLINK_MSG_ID_ESC_INFO_LEN; - memset(esc_info, 0, MAVLINK_MSG_ID_ESC_INFO_LEN); - memcpy(esc_info, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_esc_status.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_esc_status.h deleted file mode 100644 index 4254cb72..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_esc_status.h +++ /dev/null @@ -1,307 +0,0 @@ -#pragma once -// MESSAGE ESC_STATUS PACKING - -#define MAVLINK_MSG_ID_ESC_STATUS 291 - - -typedef struct __mavlink_esc_status_t { - uint64_t time_usec; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude the number.*/ - int32_t rpm[4]; /*< [rpm] Reported motor RPM from each ESC (negative for reverse rotation).*/ - float voltage[4]; /*< [V] Voltage measured from each ESC.*/ - float current[4]; /*< [A] Current measured from each ESC.*/ - uint8_t index; /*< Index of the first ESC in this message. minValue = 0, maxValue = 60, increment = 4.*/ -} mavlink_esc_status_t; - -#define MAVLINK_MSG_ID_ESC_STATUS_LEN 57 -#define MAVLINK_MSG_ID_ESC_STATUS_MIN_LEN 57 -#define MAVLINK_MSG_ID_291_LEN 57 -#define MAVLINK_MSG_ID_291_MIN_LEN 57 - -#define MAVLINK_MSG_ID_ESC_STATUS_CRC 10 -#define MAVLINK_MSG_ID_291_CRC 10 - -#define MAVLINK_MSG_ESC_STATUS_FIELD_RPM_LEN 4 -#define MAVLINK_MSG_ESC_STATUS_FIELD_VOLTAGE_LEN 4 -#define MAVLINK_MSG_ESC_STATUS_FIELD_CURRENT_LEN 4 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_ESC_STATUS { \ - 291, \ - "ESC_STATUS", \ - 5, \ - { { "index", NULL, MAVLINK_TYPE_UINT8_T, 0, 56, offsetof(mavlink_esc_status_t, index) }, \ - { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_esc_status_t, time_usec) }, \ - { "rpm", NULL, MAVLINK_TYPE_INT32_T, 4, 8, offsetof(mavlink_esc_status_t, rpm) }, \ - { "voltage", NULL, MAVLINK_TYPE_FLOAT, 4, 24, offsetof(mavlink_esc_status_t, voltage) }, \ - { "current", NULL, MAVLINK_TYPE_FLOAT, 4, 40, offsetof(mavlink_esc_status_t, current) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_ESC_STATUS { \ - "ESC_STATUS", \ - 5, \ - { { "index", NULL, MAVLINK_TYPE_UINT8_T, 0, 56, offsetof(mavlink_esc_status_t, index) }, \ - { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_esc_status_t, time_usec) }, \ - { "rpm", NULL, MAVLINK_TYPE_INT32_T, 4, 8, offsetof(mavlink_esc_status_t, rpm) }, \ - { "voltage", NULL, MAVLINK_TYPE_FLOAT, 4, 24, offsetof(mavlink_esc_status_t, voltage) }, \ - { "current", NULL, MAVLINK_TYPE_FLOAT, 4, 40, offsetof(mavlink_esc_status_t, current) }, \ - } \ -} -#endif - -/** - * @brief Pack a esc_status message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param index Index of the first ESC in this message. minValue = 0, maxValue = 60, increment = 4. - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude the number. - * @param rpm [rpm] Reported motor RPM from each ESC (negative for reverse rotation). - * @param voltage [V] Voltage measured from each ESC. - * @param current [A] Current measured from each ESC. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_esc_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t index, uint64_t time_usec, const int32_t *rpm, const float *voltage, const float *current) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_ESC_STATUS_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint8_t(buf, 56, index); - _mav_put_int32_t_array(buf, 8, rpm, 4); - _mav_put_float_array(buf, 24, voltage, 4); - _mav_put_float_array(buf, 40, current, 4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ESC_STATUS_LEN); -#else - mavlink_esc_status_t packet; - packet.time_usec = time_usec; - packet.index = index; - mav_array_memcpy(packet.rpm, rpm, sizeof(int32_t)*4); - mav_array_memcpy(packet.voltage, voltage, sizeof(float)*4); - mav_array_memcpy(packet.current, current, sizeof(float)*4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ESC_STATUS_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_ESC_STATUS; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ESC_STATUS_MIN_LEN, MAVLINK_MSG_ID_ESC_STATUS_LEN, MAVLINK_MSG_ID_ESC_STATUS_CRC); -} - -/** - * @brief Pack a esc_status message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param index Index of the first ESC in this message. minValue = 0, maxValue = 60, increment = 4. - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude the number. - * @param rpm [rpm] Reported motor RPM from each ESC (negative for reverse rotation). - * @param voltage [V] Voltage measured from each ESC. - * @param current [A] Current measured from each ESC. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_esc_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t index,uint64_t time_usec,const int32_t *rpm,const float *voltage,const float *current) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_ESC_STATUS_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint8_t(buf, 56, index); - _mav_put_int32_t_array(buf, 8, rpm, 4); - _mav_put_float_array(buf, 24, voltage, 4); - _mav_put_float_array(buf, 40, current, 4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ESC_STATUS_LEN); -#else - mavlink_esc_status_t packet; - packet.time_usec = time_usec; - packet.index = index; - mav_array_memcpy(packet.rpm, rpm, sizeof(int32_t)*4); - mav_array_memcpy(packet.voltage, voltage, sizeof(float)*4); - mav_array_memcpy(packet.current, current, sizeof(float)*4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ESC_STATUS_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_ESC_STATUS; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ESC_STATUS_MIN_LEN, MAVLINK_MSG_ID_ESC_STATUS_LEN, MAVLINK_MSG_ID_ESC_STATUS_CRC); -} - -/** - * @brief Encode a esc_status struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param esc_status C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_esc_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_esc_status_t* esc_status) -{ - return mavlink_msg_esc_status_pack(system_id, component_id, msg, esc_status->index, esc_status->time_usec, esc_status->rpm, esc_status->voltage, esc_status->current); -} - -/** - * @brief Encode a esc_status struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param esc_status C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_esc_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_esc_status_t* esc_status) -{ - return mavlink_msg_esc_status_pack_chan(system_id, component_id, chan, msg, esc_status->index, esc_status->time_usec, esc_status->rpm, esc_status->voltage, esc_status->current); -} - -/** - * @brief Send a esc_status message - * @param chan MAVLink channel to send the message - * - * @param index Index of the first ESC in this message. minValue = 0, maxValue = 60, increment = 4. - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude the number. - * @param rpm [rpm] Reported motor RPM from each ESC (negative for reverse rotation). - * @param voltage [V] Voltage measured from each ESC. - * @param current [A] Current measured from each ESC. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_esc_status_send(mavlink_channel_t chan, uint8_t index, uint64_t time_usec, const int32_t *rpm, const float *voltage, const float *current) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_ESC_STATUS_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint8_t(buf, 56, index); - _mav_put_int32_t_array(buf, 8, rpm, 4); - _mav_put_float_array(buf, 24, voltage, 4); - _mav_put_float_array(buf, 40, current, 4); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ESC_STATUS, buf, MAVLINK_MSG_ID_ESC_STATUS_MIN_LEN, MAVLINK_MSG_ID_ESC_STATUS_LEN, MAVLINK_MSG_ID_ESC_STATUS_CRC); -#else - mavlink_esc_status_t packet; - packet.time_usec = time_usec; - packet.index = index; - mav_array_memcpy(packet.rpm, rpm, sizeof(int32_t)*4); - mav_array_memcpy(packet.voltage, voltage, sizeof(float)*4); - mav_array_memcpy(packet.current, current, sizeof(float)*4); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ESC_STATUS, (const char *)&packet, MAVLINK_MSG_ID_ESC_STATUS_MIN_LEN, MAVLINK_MSG_ID_ESC_STATUS_LEN, MAVLINK_MSG_ID_ESC_STATUS_CRC); -#endif -} - -/** - * @brief Send a esc_status message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_esc_status_send_struct(mavlink_channel_t chan, const mavlink_esc_status_t* esc_status) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_esc_status_send(chan, esc_status->index, esc_status->time_usec, esc_status->rpm, esc_status->voltage, esc_status->current); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ESC_STATUS, (const char *)esc_status, MAVLINK_MSG_ID_ESC_STATUS_MIN_LEN, MAVLINK_MSG_ID_ESC_STATUS_LEN, MAVLINK_MSG_ID_ESC_STATUS_CRC); -#endif -} - -#if MAVLINK_MSG_ID_ESC_STATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_esc_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t index, uint64_t time_usec, const int32_t *rpm, const float *voltage, const float *current) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint8_t(buf, 56, index); - _mav_put_int32_t_array(buf, 8, rpm, 4); - _mav_put_float_array(buf, 24, voltage, 4); - _mav_put_float_array(buf, 40, current, 4); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ESC_STATUS, buf, MAVLINK_MSG_ID_ESC_STATUS_MIN_LEN, MAVLINK_MSG_ID_ESC_STATUS_LEN, MAVLINK_MSG_ID_ESC_STATUS_CRC); -#else - mavlink_esc_status_t *packet = (mavlink_esc_status_t *)msgbuf; - packet->time_usec = time_usec; - packet->index = index; - mav_array_memcpy(packet->rpm, rpm, sizeof(int32_t)*4); - mav_array_memcpy(packet->voltage, voltage, sizeof(float)*4); - mav_array_memcpy(packet->current, current, sizeof(float)*4); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ESC_STATUS, (const char *)packet, MAVLINK_MSG_ID_ESC_STATUS_MIN_LEN, MAVLINK_MSG_ID_ESC_STATUS_LEN, MAVLINK_MSG_ID_ESC_STATUS_CRC); -#endif -} -#endif - -#endif - -// MESSAGE ESC_STATUS UNPACKING - - -/** - * @brief Get field index from esc_status message - * - * @return Index of the first ESC in this message. minValue = 0, maxValue = 60, increment = 4. - */ -static inline uint8_t mavlink_msg_esc_status_get_index(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 56); -} - -/** - * @brief Get field time_usec from esc_status message - * - * @return [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude the number. - */ -static inline uint64_t mavlink_msg_esc_status_get_time_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field rpm from esc_status message - * - * @return [rpm] Reported motor RPM from each ESC (negative for reverse rotation). - */ -static inline uint16_t mavlink_msg_esc_status_get_rpm(const mavlink_message_t* msg, int32_t *rpm) -{ - return _MAV_RETURN_int32_t_array(msg, rpm, 4, 8); -} - -/** - * @brief Get field voltage from esc_status message - * - * @return [V] Voltage measured from each ESC. - */ -static inline uint16_t mavlink_msg_esc_status_get_voltage(const mavlink_message_t* msg, float *voltage) -{ - return _MAV_RETURN_float_array(msg, voltage, 4, 24); -} - -/** - * @brief Get field current from esc_status message - * - * @return [A] Current measured from each ESC. - */ -static inline uint16_t mavlink_msg_esc_status_get_current(const mavlink_message_t* msg, float *current) -{ - return _MAV_RETURN_float_array(msg, current, 4, 40); -} - -/** - * @brief Decode a esc_status message into a struct - * - * @param msg The message to decode - * @param esc_status C-struct to decode the message contents into - */ -static inline void mavlink_msg_esc_status_decode(const mavlink_message_t* msg, mavlink_esc_status_t* esc_status) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - esc_status->time_usec = mavlink_msg_esc_status_get_time_usec(msg); - mavlink_msg_esc_status_get_rpm(msg, esc_status->rpm); - mavlink_msg_esc_status_get_voltage(msg, esc_status->voltage); - mavlink_msg_esc_status_get_current(msg, esc_status->current); - esc_status->index = mavlink_msg_esc_status_get_index(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_ESC_STATUS_LEN? msg->len : MAVLINK_MSG_ID_ESC_STATUS_LEN; - memset(esc_status, 0, MAVLINK_MSG_ID_ESC_STATUS_LEN); - memcpy(esc_status, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_estimator_status.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_estimator_status.h deleted file mode 100644 index 21ef9a67..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_estimator_status.h +++ /dev/null @@ -1,438 +0,0 @@ -#pragma once -// MESSAGE ESTIMATOR_STATUS PACKING - -#define MAVLINK_MSG_ID_ESTIMATOR_STATUS 230 - - -typedef struct __mavlink_estimator_status_t { - uint64_t time_usec; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/ - float vel_ratio; /*< Velocity innovation test ratio*/ - float pos_horiz_ratio; /*< Horizontal position innovation test ratio*/ - float pos_vert_ratio; /*< Vertical position innovation test ratio*/ - float mag_ratio; /*< Magnetometer innovation test ratio*/ - float hagl_ratio; /*< Height above terrain innovation test ratio*/ - float tas_ratio; /*< True airspeed innovation test ratio*/ - float pos_horiz_accuracy; /*< [m] Horizontal position 1-STD accuracy relative to the EKF local origin*/ - float pos_vert_accuracy; /*< [m] Vertical position 1-STD accuracy relative to the EKF local origin*/ - uint16_t flags; /*< Bitmap indicating which EKF outputs are valid.*/ -} mavlink_estimator_status_t; - -#define MAVLINK_MSG_ID_ESTIMATOR_STATUS_LEN 42 -#define MAVLINK_MSG_ID_ESTIMATOR_STATUS_MIN_LEN 42 -#define MAVLINK_MSG_ID_230_LEN 42 -#define MAVLINK_MSG_ID_230_MIN_LEN 42 - -#define MAVLINK_MSG_ID_ESTIMATOR_STATUS_CRC 163 -#define MAVLINK_MSG_ID_230_CRC 163 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_ESTIMATOR_STATUS { \ - 230, \ - "ESTIMATOR_STATUS", \ - 10, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_estimator_status_t, time_usec) }, \ - { "flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 40, offsetof(mavlink_estimator_status_t, flags) }, \ - { "vel_ratio", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_estimator_status_t, vel_ratio) }, \ - { "pos_horiz_ratio", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_estimator_status_t, pos_horiz_ratio) }, \ - { "pos_vert_ratio", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_estimator_status_t, pos_vert_ratio) }, \ - { "mag_ratio", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_estimator_status_t, mag_ratio) }, \ - { "hagl_ratio", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_estimator_status_t, hagl_ratio) }, \ - { "tas_ratio", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_estimator_status_t, tas_ratio) }, \ - { "pos_horiz_accuracy", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_estimator_status_t, pos_horiz_accuracy) }, \ - { "pos_vert_accuracy", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_estimator_status_t, pos_vert_accuracy) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_ESTIMATOR_STATUS { \ - "ESTIMATOR_STATUS", \ - 10, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_estimator_status_t, time_usec) }, \ - { "flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 40, offsetof(mavlink_estimator_status_t, flags) }, \ - { "vel_ratio", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_estimator_status_t, vel_ratio) }, \ - { "pos_horiz_ratio", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_estimator_status_t, pos_horiz_ratio) }, \ - { "pos_vert_ratio", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_estimator_status_t, pos_vert_ratio) }, \ - { "mag_ratio", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_estimator_status_t, mag_ratio) }, \ - { "hagl_ratio", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_estimator_status_t, hagl_ratio) }, \ - { "tas_ratio", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_estimator_status_t, tas_ratio) }, \ - { "pos_horiz_accuracy", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_estimator_status_t, pos_horiz_accuracy) }, \ - { "pos_vert_accuracy", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_estimator_status_t, pos_vert_accuracy) }, \ - } \ -} -#endif - -/** - * @brief Pack a estimator_status message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @param flags Bitmap indicating which EKF outputs are valid. - * @param vel_ratio Velocity innovation test ratio - * @param pos_horiz_ratio Horizontal position innovation test ratio - * @param pos_vert_ratio Vertical position innovation test ratio - * @param mag_ratio Magnetometer innovation test ratio - * @param hagl_ratio Height above terrain innovation test ratio - * @param tas_ratio True airspeed innovation test ratio - * @param pos_horiz_accuracy [m] Horizontal position 1-STD accuracy relative to the EKF local origin - * @param pos_vert_accuracy [m] Vertical position 1-STD accuracy relative to the EKF local origin - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_estimator_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint64_t time_usec, uint16_t flags, float vel_ratio, float pos_horiz_ratio, float pos_vert_ratio, float mag_ratio, float hagl_ratio, float tas_ratio, float pos_horiz_accuracy, float pos_vert_accuracy) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_ESTIMATOR_STATUS_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, vel_ratio); - _mav_put_float(buf, 12, pos_horiz_ratio); - _mav_put_float(buf, 16, pos_vert_ratio); - _mav_put_float(buf, 20, mag_ratio); - _mav_put_float(buf, 24, hagl_ratio); - _mav_put_float(buf, 28, tas_ratio); - _mav_put_float(buf, 32, pos_horiz_accuracy); - _mav_put_float(buf, 36, pos_vert_accuracy); - _mav_put_uint16_t(buf, 40, flags); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ESTIMATOR_STATUS_LEN); -#else - mavlink_estimator_status_t packet; - packet.time_usec = time_usec; - packet.vel_ratio = vel_ratio; - packet.pos_horiz_ratio = pos_horiz_ratio; - packet.pos_vert_ratio = pos_vert_ratio; - packet.mag_ratio = mag_ratio; - packet.hagl_ratio = hagl_ratio; - packet.tas_ratio = tas_ratio; - packet.pos_horiz_accuracy = pos_horiz_accuracy; - packet.pos_vert_accuracy = pos_vert_accuracy; - packet.flags = flags; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ESTIMATOR_STATUS_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_ESTIMATOR_STATUS; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ESTIMATOR_STATUS_MIN_LEN, MAVLINK_MSG_ID_ESTIMATOR_STATUS_LEN, MAVLINK_MSG_ID_ESTIMATOR_STATUS_CRC); -} - -/** - * @brief Pack a estimator_status message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @param flags Bitmap indicating which EKF outputs are valid. - * @param vel_ratio Velocity innovation test ratio - * @param pos_horiz_ratio Horizontal position innovation test ratio - * @param pos_vert_ratio Vertical position innovation test ratio - * @param mag_ratio Magnetometer innovation test ratio - * @param hagl_ratio Height above terrain innovation test ratio - * @param tas_ratio True airspeed innovation test ratio - * @param pos_horiz_accuracy [m] Horizontal position 1-STD accuracy relative to the EKF local origin - * @param pos_vert_accuracy [m] Vertical position 1-STD accuracy relative to the EKF local origin - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_estimator_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint64_t time_usec,uint16_t flags,float vel_ratio,float pos_horiz_ratio,float pos_vert_ratio,float mag_ratio,float hagl_ratio,float tas_ratio,float pos_horiz_accuracy,float pos_vert_accuracy) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_ESTIMATOR_STATUS_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, vel_ratio); - _mav_put_float(buf, 12, pos_horiz_ratio); - _mav_put_float(buf, 16, pos_vert_ratio); - _mav_put_float(buf, 20, mag_ratio); - _mav_put_float(buf, 24, hagl_ratio); - _mav_put_float(buf, 28, tas_ratio); - _mav_put_float(buf, 32, pos_horiz_accuracy); - _mav_put_float(buf, 36, pos_vert_accuracy); - _mav_put_uint16_t(buf, 40, flags); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ESTIMATOR_STATUS_LEN); -#else - mavlink_estimator_status_t packet; - packet.time_usec = time_usec; - packet.vel_ratio = vel_ratio; - packet.pos_horiz_ratio = pos_horiz_ratio; - packet.pos_vert_ratio = pos_vert_ratio; - packet.mag_ratio = mag_ratio; - packet.hagl_ratio = hagl_ratio; - packet.tas_ratio = tas_ratio; - packet.pos_horiz_accuracy = pos_horiz_accuracy; - packet.pos_vert_accuracy = pos_vert_accuracy; - packet.flags = flags; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ESTIMATOR_STATUS_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_ESTIMATOR_STATUS; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ESTIMATOR_STATUS_MIN_LEN, MAVLINK_MSG_ID_ESTIMATOR_STATUS_LEN, MAVLINK_MSG_ID_ESTIMATOR_STATUS_CRC); -} - -/** - * @brief Encode a estimator_status struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param estimator_status C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_estimator_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_estimator_status_t* estimator_status) -{ - return mavlink_msg_estimator_status_pack(system_id, component_id, msg, estimator_status->time_usec, estimator_status->flags, estimator_status->vel_ratio, estimator_status->pos_horiz_ratio, estimator_status->pos_vert_ratio, estimator_status->mag_ratio, estimator_status->hagl_ratio, estimator_status->tas_ratio, estimator_status->pos_horiz_accuracy, estimator_status->pos_vert_accuracy); -} - -/** - * @brief Encode a estimator_status struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param estimator_status C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_estimator_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_estimator_status_t* estimator_status) -{ - return mavlink_msg_estimator_status_pack_chan(system_id, component_id, chan, msg, estimator_status->time_usec, estimator_status->flags, estimator_status->vel_ratio, estimator_status->pos_horiz_ratio, estimator_status->pos_vert_ratio, estimator_status->mag_ratio, estimator_status->hagl_ratio, estimator_status->tas_ratio, estimator_status->pos_horiz_accuracy, estimator_status->pos_vert_accuracy); -} - -/** - * @brief Send a estimator_status message - * @param chan MAVLink channel to send the message - * - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @param flags Bitmap indicating which EKF outputs are valid. - * @param vel_ratio Velocity innovation test ratio - * @param pos_horiz_ratio Horizontal position innovation test ratio - * @param pos_vert_ratio Vertical position innovation test ratio - * @param mag_ratio Magnetometer innovation test ratio - * @param hagl_ratio Height above terrain innovation test ratio - * @param tas_ratio True airspeed innovation test ratio - * @param pos_horiz_accuracy [m] Horizontal position 1-STD accuracy relative to the EKF local origin - * @param pos_vert_accuracy [m] Vertical position 1-STD accuracy relative to the EKF local origin - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_estimator_status_send(mavlink_channel_t chan, uint64_t time_usec, uint16_t flags, float vel_ratio, float pos_horiz_ratio, float pos_vert_ratio, float mag_ratio, float hagl_ratio, float tas_ratio, float pos_horiz_accuracy, float pos_vert_accuracy) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_ESTIMATOR_STATUS_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, vel_ratio); - _mav_put_float(buf, 12, pos_horiz_ratio); - _mav_put_float(buf, 16, pos_vert_ratio); - _mav_put_float(buf, 20, mag_ratio); - _mav_put_float(buf, 24, hagl_ratio); - _mav_put_float(buf, 28, tas_ratio); - _mav_put_float(buf, 32, pos_horiz_accuracy); - _mav_put_float(buf, 36, pos_vert_accuracy); - _mav_put_uint16_t(buf, 40, flags); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ESTIMATOR_STATUS, buf, MAVLINK_MSG_ID_ESTIMATOR_STATUS_MIN_LEN, MAVLINK_MSG_ID_ESTIMATOR_STATUS_LEN, MAVLINK_MSG_ID_ESTIMATOR_STATUS_CRC); -#else - mavlink_estimator_status_t packet; - packet.time_usec = time_usec; - packet.vel_ratio = vel_ratio; - packet.pos_horiz_ratio = pos_horiz_ratio; - packet.pos_vert_ratio = pos_vert_ratio; - packet.mag_ratio = mag_ratio; - packet.hagl_ratio = hagl_ratio; - packet.tas_ratio = tas_ratio; - packet.pos_horiz_accuracy = pos_horiz_accuracy; - packet.pos_vert_accuracy = pos_vert_accuracy; - packet.flags = flags; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ESTIMATOR_STATUS, (const char *)&packet, MAVLINK_MSG_ID_ESTIMATOR_STATUS_MIN_LEN, MAVLINK_MSG_ID_ESTIMATOR_STATUS_LEN, MAVLINK_MSG_ID_ESTIMATOR_STATUS_CRC); -#endif -} - -/** - * @brief Send a estimator_status message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_estimator_status_send_struct(mavlink_channel_t chan, const mavlink_estimator_status_t* estimator_status) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_estimator_status_send(chan, estimator_status->time_usec, estimator_status->flags, estimator_status->vel_ratio, estimator_status->pos_horiz_ratio, estimator_status->pos_vert_ratio, estimator_status->mag_ratio, estimator_status->hagl_ratio, estimator_status->tas_ratio, estimator_status->pos_horiz_accuracy, estimator_status->pos_vert_accuracy); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ESTIMATOR_STATUS, (const char *)estimator_status, MAVLINK_MSG_ID_ESTIMATOR_STATUS_MIN_LEN, MAVLINK_MSG_ID_ESTIMATOR_STATUS_LEN, MAVLINK_MSG_ID_ESTIMATOR_STATUS_CRC); -#endif -} - -#if MAVLINK_MSG_ID_ESTIMATOR_STATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_estimator_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, uint16_t flags, float vel_ratio, float pos_horiz_ratio, float pos_vert_ratio, float mag_ratio, float hagl_ratio, float tas_ratio, float pos_horiz_accuracy, float pos_vert_accuracy) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, vel_ratio); - _mav_put_float(buf, 12, pos_horiz_ratio); - _mav_put_float(buf, 16, pos_vert_ratio); - _mav_put_float(buf, 20, mag_ratio); - _mav_put_float(buf, 24, hagl_ratio); - _mav_put_float(buf, 28, tas_ratio); - _mav_put_float(buf, 32, pos_horiz_accuracy); - _mav_put_float(buf, 36, pos_vert_accuracy); - _mav_put_uint16_t(buf, 40, flags); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ESTIMATOR_STATUS, buf, MAVLINK_MSG_ID_ESTIMATOR_STATUS_MIN_LEN, MAVLINK_MSG_ID_ESTIMATOR_STATUS_LEN, MAVLINK_MSG_ID_ESTIMATOR_STATUS_CRC); -#else - mavlink_estimator_status_t *packet = (mavlink_estimator_status_t *)msgbuf; - packet->time_usec = time_usec; - packet->vel_ratio = vel_ratio; - packet->pos_horiz_ratio = pos_horiz_ratio; - packet->pos_vert_ratio = pos_vert_ratio; - packet->mag_ratio = mag_ratio; - packet->hagl_ratio = hagl_ratio; - packet->tas_ratio = tas_ratio; - packet->pos_horiz_accuracy = pos_horiz_accuracy; - packet->pos_vert_accuracy = pos_vert_accuracy; - packet->flags = flags; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ESTIMATOR_STATUS, (const char *)packet, MAVLINK_MSG_ID_ESTIMATOR_STATUS_MIN_LEN, MAVLINK_MSG_ID_ESTIMATOR_STATUS_LEN, MAVLINK_MSG_ID_ESTIMATOR_STATUS_CRC); -#endif -} -#endif - -#endif - -// MESSAGE ESTIMATOR_STATUS UNPACKING - - -/** - * @brief Get field time_usec from estimator_status message - * - * @return [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - */ -static inline uint64_t mavlink_msg_estimator_status_get_time_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field flags from estimator_status message - * - * @return Bitmap indicating which EKF outputs are valid. - */ -static inline uint16_t mavlink_msg_estimator_status_get_flags(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 40); -} - -/** - * @brief Get field vel_ratio from estimator_status message - * - * @return Velocity innovation test ratio - */ -static inline float mavlink_msg_estimator_status_get_vel_ratio(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field pos_horiz_ratio from estimator_status message - * - * @return Horizontal position innovation test ratio - */ -static inline float mavlink_msg_estimator_status_get_pos_horiz_ratio(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field pos_vert_ratio from estimator_status message - * - * @return Vertical position innovation test ratio - */ -static inline float mavlink_msg_estimator_status_get_pos_vert_ratio(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field mag_ratio from estimator_status message - * - * @return Magnetometer innovation test ratio - */ -static inline float mavlink_msg_estimator_status_get_mag_ratio(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Get field hagl_ratio from estimator_status message - * - * @return Height above terrain innovation test ratio - */ -static inline float mavlink_msg_estimator_status_get_hagl_ratio(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Get field tas_ratio from estimator_status message - * - * @return True airspeed innovation test ratio - */ -static inline float mavlink_msg_estimator_status_get_tas_ratio(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 28); -} - -/** - * @brief Get field pos_horiz_accuracy from estimator_status message - * - * @return [m] Horizontal position 1-STD accuracy relative to the EKF local origin - */ -static inline float mavlink_msg_estimator_status_get_pos_horiz_accuracy(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 32); -} - -/** - * @brief Get field pos_vert_accuracy from estimator_status message - * - * @return [m] Vertical position 1-STD accuracy relative to the EKF local origin - */ -static inline float mavlink_msg_estimator_status_get_pos_vert_accuracy(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 36); -} - -/** - * @brief Decode a estimator_status message into a struct - * - * @param msg The message to decode - * @param estimator_status C-struct to decode the message contents into - */ -static inline void mavlink_msg_estimator_status_decode(const mavlink_message_t* msg, mavlink_estimator_status_t* estimator_status) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - estimator_status->time_usec = mavlink_msg_estimator_status_get_time_usec(msg); - estimator_status->vel_ratio = mavlink_msg_estimator_status_get_vel_ratio(msg); - estimator_status->pos_horiz_ratio = mavlink_msg_estimator_status_get_pos_horiz_ratio(msg); - estimator_status->pos_vert_ratio = mavlink_msg_estimator_status_get_pos_vert_ratio(msg); - estimator_status->mag_ratio = mavlink_msg_estimator_status_get_mag_ratio(msg); - estimator_status->hagl_ratio = mavlink_msg_estimator_status_get_hagl_ratio(msg); - estimator_status->tas_ratio = mavlink_msg_estimator_status_get_tas_ratio(msg); - estimator_status->pos_horiz_accuracy = mavlink_msg_estimator_status_get_pos_horiz_accuracy(msg); - estimator_status->pos_vert_accuracy = mavlink_msg_estimator_status_get_pos_vert_accuracy(msg); - estimator_status->flags = mavlink_msg_estimator_status_get_flags(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_ESTIMATOR_STATUS_LEN? msg->len : MAVLINK_MSG_ID_ESTIMATOR_STATUS_LEN; - memset(estimator_status, 0, MAVLINK_MSG_ID_ESTIMATOR_STATUS_LEN); - memcpy(estimator_status, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_event.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_event.h deleted file mode 100644 index 7c419849..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_event.h +++ /dev/null @@ -1,355 +0,0 @@ -#pragma once -// MESSAGE EVENT PACKING - -#define MAVLINK_MSG_ID_EVENT 410 - - -typedef struct __mavlink_event_t { - uint32_t id; /*< Event ID (as defined in the component metadata)*/ - uint32_t event_time_boot_ms; /*< [ms] Timestamp (time since system boot when the event happened).*/ - uint16_t sequence; /*< Sequence number.*/ - uint8_t destination_component; /*< Component ID*/ - uint8_t destination_system; /*< System ID*/ - uint8_t log_levels; /*< Log levels: 4 bits MSB: internal (for logging purposes), 4 bits LSB: external. Levels: Emergency = 0, Alert = 1, Critical = 2, Error = 3, Warning = 4, Notice = 5, Info = 6, Debug = 7, Protocol = 8, Disabled = 9*/ - uint8_t arguments[40]; /*< Arguments (depend on event ID).*/ -} mavlink_event_t; - -#define MAVLINK_MSG_ID_EVENT_LEN 53 -#define MAVLINK_MSG_ID_EVENT_MIN_LEN 53 -#define MAVLINK_MSG_ID_410_LEN 53 -#define MAVLINK_MSG_ID_410_MIN_LEN 53 - -#define MAVLINK_MSG_ID_EVENT_CRC 160 -#define MAVLINK_MSG_ID_410_CRC 160 - -#define MAVLINK_MSG_EVENT_FIELD_ARGUMENTS_LEN 40 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_EVENT { \ - 410, \ - "EVENT", \ - 7, \ - { { "destination_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_event_t, destination_component) }, \ - { "destination_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_event_t, destination_system) }, \ - { "id", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_event_t, id) }, \ - { "event_time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_event_t, event_time_boot_ms) }, \ - { "sequence", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_event_t, sequence) }, \ - { "log_levels", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_event_t, log_levels) }, \ - { "arguments", NULL, MAVLINK_TYPE_UINT8_T, 40, 13, offsetof(mavlink_event_t, arguments) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_EVENT { \ - "EVENT", \ - 7, \ - { { "destination_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_event_t, destination_component) }, \ - { "destination_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_event_t, destination_system) }, \ - { "id", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_event_t, id) }, \ - { "event_time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_event_t, event_time_boot_ms) }, \ - { "sequence", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_event_t, sequence) }, \ - { "log_levels", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_event_t, log_levels) }, \ - { "arguments", NULL, MAVLINK_TYPE_UINT8_T, 40, 13, offsetof(mavlink_event_t, arguments) }, \ - } \ -} -#endif - -/** - * @brief Pack a event message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param destination_component Component ID - * @param destination_system System ID - * @param id Event ID (as defined in the component metadata) - * @param event_time_boot_ms [ms] Timestamp (time since system boot when the event happened). - * @param sequence Sequence number. - * @param log_levels Log levels: 4 bits MSB: internal (for logging purposes), 4 bits LSB: external. Levels: Emergency = 0, Alert = 1, Critical = 2, Error = 3, Warning = 4, Notice = 5, Info = 6, Debug = 7, Protocol = 8, Disabled = 9 - * @param arguments Arguments (depend on event ID). - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_event_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t destination_component, uint8_t destination_system, uint32_t id, uint32_t event_time_boot_ms, uint16_t sequence, uint8_t log_levels, const uint8_t *arguments) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_EVENT_LEN]; - _mav_put_uint32_t(buf, 0, id); - _mav_put_uint32_t(buf, 4, event_time_boot_ms); - _mav_put_uint16_t(buf, 8, sequence); - _mav_put_uint8_t(buf, 10, destination_component); - _mav_put_uint8_t(buf, 11, destination_system); - _mav_put_uint8_t(buf, 12, log_levels); - _mav_put_uint8_t_array(buf, 13, arguments, 40); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_EVENT_LEN); -#else - mavlink_event_t packet; - packet.id = id; - packet.event_time_boot_ms = event_time_boot_ms; - packet.sequence = sequence; - packet.destination_component = destination_component; - packet.destination_system = destination_system; - packet.log_levels = log_levels; - mav_array_memcpy(packet.arguments, arguments, sizeof(uint8_t)*40); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_EVENT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_EVENT; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_EVENT_MIN_LEN, MAVLINK_MSG_ID_EVENT_LEN, MAVLINK_MSG_ID_EVENT_CRC); -} - -/** - * @brief Pack a event message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param destination_component Component ID - * @param destination_system System ID - * @param id Event ID (as defined in the component metadata) - * @param event_time_boot_ms [ms] Timestamp (time since system boot when the event happened). - * @param sequence Sequence number. - * @param log_levels Log levels: 4 bits MSB: internal (for logging purposes), 4 bits LSB: external. Levels: Emergency = 0, Alert = 1, Critical = 2, Error = 3, Warning = 4, Notice = 5, Info = 6, Debug = 7, Protocol = 8, Disabled = 9 - * @param arguments Arguments (depend on event ID). - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_event_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t destination_component,uint8_t destination_system,uint32_t id,uint32_t event_time_boot_ms,uint16_t sequence,uint8_t log_levels,const uint8_t *arguments) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_EVENT_LEN]; - _mav_put_uint32_t(buf, 0, id); - _mav_put_uint32_t(buf, 4, event_time_boot_ms); - _mav_put_uint16_t(buf, 8, sequence); - _mav_put_uint8_t(buf, 10, destination_component); - _mav_put_uint8_t(buf, 11, destination_system); - _mav_put_uint8_t(buf, 12, log_levels); - _mav_put_uint8_t_array(buf, 13, arguments, 40); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_EVENT_LEN); -#else - mavlink_event_t packet; - packet.id = id; - packet.event_time_boot_ms = event_time_boot_ms; - packet.sequence = sequence; - packet.destination_component = destination_component; - packet.destination_system = destination_system; - packet.log_levels = log_levels; - mav_array_memcpy(packet.arguments, arguments, sizeof(uint8_t)*40); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_EVENT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_EVENT; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_EVENT_MIN_LEN, MAVLINK_MSG_ID_EVENT_LEN, MAVLINK_MSG_ID_EVENT_CRC); -} - -/** - * @brief Encode a event struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param event C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_event_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_event_t* event) -{ - return mavlink_msg_event_pack(system_id, component_id, msg, event->destination_component, event->destination_system, event->id, event->event_time_boot_ms, event->sequence, event->log_levels, event->arguments); -} - -/** - * @brief Encode a event struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param event C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_event_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_event_t* event) -{ - return mavlink_msg_event_pack_chan(system_id, component_id, chan, msg, event->destination_component, event->destination_system, event->id, event->event_time_boot_ms, event->sequence, event->log_levels, event->arguments); -} - -/** - * @brief Send a event message - * @param chan MAVLink channel to send the message - * - * @param destination_component Component ID - * @param destination_system System ID - * @param id Event ID (as defined in the component metadata) - * @param event_time_boot_ms [ms] Timestamp (time since system boot when the event happened). - * @param sequence Sequence number. - * @param log_levels Log levels: 4 bits MSB: internal (for logging purposes), 4 bits LSB: external. Levels: Emergency = 0, Alert = 1, Critical = 2, Error = 3, Warning = 4, Notice = 5, Info = 6, Debug = 7, Protocol = 8, Disabled = 9 - * @param arguments Arguments (depend on event ID). - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_event_send(mavlink_channel_t chan, uint8_t destination_component, uint8_t destination_system, uint32_t id, uint32_t event_time_boot_ms, uint16_t sequence, uint8_t log_levels, const uint8_t *arguments) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_EVENT_LEN]; - _mav_put_uint32_t(buf, 0, id); - _mav_put_uint32_t(buf, 4, event_time_boot_ms); - _mav_put_uint16_t(buf, 8, sequence); - _mav_put_uint8_t(buf, 10, destination_component); - _mav_put_uint8_t(buf, 11, destination_system); - _mav_put_uint8_t(buf, 12, log_levels); - _mav_put_uint8_t_array(buf, 13, arguments, 40); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_EVENT, buf, MAVLINK_MSG_ID_EVENT_MIN_LEN, MAVLINK_MSG_ID_EVENT_LEN, MAVLINK_MSG_ID_EVENT_CRC); -#else - mavlink_event_t packet; - packet.id = id; - packet.event_time_boot_ms = event_time_boot_ms; - packet.sequence = sequence; - packet.destination_component = destination_component; - packet.destination_system = destination_system; - packet.log_levels = log_levels; - mav_array_memcpy(packet.arguments, arguments, sizeof(uint8_t)*40); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_EVENT, (const char *)&packet, MAVLINK_MSG_ID_EVENT_MIN_LEN, MAVLINK_MSG_ID_EVENT_LEN, MAVLINK_MSG_ID_EVENT_CRC); -#endif -} - -/** - * @brief Send a event message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_event_send_struct(mavlink_channel_t chan, const mavlink_event_t* event) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_event_send(chan, event->destination_component, event->destination_system, event->id, event->event_time_boot_ms, event->sequence, event->log_levels, event->arguments); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_EVENT, (const char *)event, MAVLINK_MSG_ID_EVENT_MIN_LEN, MAVLINK_MSG_ID_EVENT_LEN, MAVLINK_MSG_ID_EVENT_CRC); -#endif -} - -#if MAVLINK_MSG_ID_EVENT_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_event_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t destination_component, uint8_t destination_system, uint32_t id, uint32_t event_time_boot_ms, uint16_t sequence, uint8_t log_levels, const uint8_t *arguments) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, id); - _mav_put_uint32_t(buf, 4, event_time_boot_ms); - _mav_put_uint16_t(buf, 8, sequence); - _mav_put_uint8_t(buf, 10, destination_component); - _mav_put_uint8_t(buf, 11, destination_system); - _mav_put_uint8_t(buf, 12, log_levels); - _mav_put_uint8_t_array(buf, 13, arguments, 40); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_EVENT, buf, MAVLINK_MSG_ID_EVENT_MIN_LEN, MAVLINK_MSG_ID_EVENT_LEN, MAVLINK_MSG_ID_EVENT_CRC); -#else - mavlink_event_t *packet = (mavlink_event_t *)msgbuf; - packet->id = id; - packet->event_time_boot_ms = event_time_boot_ms; - packet->sequence = sequence; - packet->destination_component = destination_component; - packet->destination_system = destination_system; - packet->log_levels = log_levels; - mav_array_memcpy(packet->arguments, arguments, sizeof(uint8_t)*40); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_EVENT, (const char *)packet, MAVLINK_MSG_ID_EVENT_MIN_LEN, MAVLINK_MSG_ID_EVENT_LEN, MAVLINK_MSG_ID_EVENT_CRC); -#endif -} -#endif - -#endif - -// MESSAGE EVENT UNPACKING - - -/** - * @brief Get field destination_component from event message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_event_get_destination_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 10); -} - -/** - * @brief Get field destination_system from event message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_event_get_destination_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 11); -} - -/** - * @brief Get field id from event message - * - * @return Event ID (as defined in the component metadata) - */ -static inline uint32_t mavlink_msg_event_get_id(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field event_time_boot_ms from event message - * - * @return [ms] Timestamp (time since system boot when the event happened). - */ -static inline uint32_t mavlink_msg_event_get_event_time_boot_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 4); -} - -/** - * @brief Get field sequence from event message - * - * @return Sequence number. - */ -static inline uint16_t mavlink_msg_event_get_sequence(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 8); -} - -/** - * @brief Get field log_levels from event message - * - * @return Log levels: 4 bits MSB: internal (for logging purposes), 4 bits LSB: external. Levels: Emergency = 0, Alert = 1, Critical = 2, Error = 3, Warning = 4, Notice = 5, Info = 6, Debug = 7, Protocol = 8, Disabled = 9 - */ -static inline uint8_t mavlink_msg_event_get_log_levels(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 12); -} - -/** - * @brief Get field arguments from event message - * - * @return Arguments (depend on event ID). - */ -static inline uint16_t mavlink_msg_event_get_arguments(const mavlink_message_t* msg, uint8_t *arguments) -{ - return _MAV_RETURN_uint8_t_array(msg, arguments, 40, 13); -} - -/** - * @brief Decode a event message into a struct - * - * @param msg The message to decode - * @param event C-struct to decode the message contents into - */ -static inline void mavlink_msg_event_decode(const mavlink_message_t* msg, mavlink_event_t* event) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - event->id = mavlink_msg_event_get_id(msg); - event->event_time_boot_ms = mavlink_msg_event_get_event_time_boot_ms(msg); - event->sequence = mavlink_msg_event_get_sequence(msg); - event->destination_component = mavlink_msg_event_get_destination_component(msg); - event->destination_system = mavlink_msg_event_get_destination_system(msg); - event->log_levels = mavlink_msg_event_get_log_levels(msg); - mavlink_msg_event_get_arguments(msg, event->arguments); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_EVENT_LEN? msg->len : MAVLINK_MSG_ID_EVENT_LEN; - memset(event, 0, MAVLINK_MSG_ID_EVENT_LEN); - memcpy(event, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_extended_sys_state.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_extended_sys_state.h deleted file mode 100644 index e9bc9418..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_extended_sys_state.h +++ /dev/null @@ -1,238 +0,0 @@ -#pragma once -// MESSAGE EXTENDED_SYS_STATE PACKING - -#define MAVLINK_MSG_ID_EXTENDED_SYS_STATE 245 - - -typedef struct __mavlink_extended_sys_state_t { - uint8_t vtol_state; /*< The VTOL state if applicable. Is set to MAV_VTOL_STATE_UNDEFINED if UAV is not in VTOL configuration.*/ - uint8_t landed_state; /*< The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown.*/ -} mavlink_extended_sys_state_t; - -#define MAVLINK_MSG_ID_EXTENDED_SYS_STATE_LEN 2 -#define MAVLINK_MSG_ID_EXTENDED_SYS_STATE_MIN_LEN 2 -#define MAVLINK_MSG_ID_245_LEN 2 -#define MAVLINK_MSG_ID_245_MIN_LEN 2 - -#define MAVLINK_MSG_ID_EXTENDED_SYS_STATE_CRC 130 -#define MAVLINK_MSG_ID_245_CRC 130 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_EXTENDED_SYS_STATE { \ - 245, \ - "EXTENDED_SYS_STATE", \ - 2, \ - { { "vtol_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_extended_sys_state_t, vtol_state) }, \ - { "landed_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_extended_sys_state_t, landed_state) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_EXTENDED_SYS_STATE { \ - "EXTENDED_SYS_STATE", \ - 2, \ - { { "vtol_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_extended_sys_state_t, vtol_state) }, \ - { "landed_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_extended_sys_state_t, landed_state) }, \ - } \ -} -#endif - -/** - * @brief Pack a extended_sys_state message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param vtol_state The VTOL state if applicable. Is set to MAV_VTOL_STATE_UNDEFINED if UAV is not in VTOL configuration. - * @param landed_state The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_extended_sys_state_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t vtol_state, uint8_t landed_state) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_EXTENDED_SYS_STATE_LEN]; - _mav_put_uint8_t(buf, 0, vtol_state); - _mav_put_uint8_t(buf, 1, landed_state); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_LEN); -#else - mavlink_extended_sys_state_t packet; - packet.vtol_state = vtol_state; - packet.landed_state = landed_state; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_EXTENDED_SYS_STATE; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_MIN_LEN, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_LEN, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_CRC); -} - -/** - * @brief Pack a extended_sys_state message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param vtol_state The VTOL state if applicable. Is set to MAV_VTOL_STATE_UNDEFINED if UAV is not in VTOL configuration. - * @param landed_state The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_extended_sys_state_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t vtol_state,uint8_t landed_state) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_EXTENDED_SYS_STATE_LEN]; - _mav_put_uint8_t(buf, 0, vtol_state); - _mav_put_uint8_t(buf, 1, landed_state); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_LEN); -#else - mavlink_extended_sys_state_t packet; - packet.vtol_state = vtol_state; - packet.landed_state = landed_state; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_EXTENDED_SYS_STATE; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_MIN_LEN, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_LEN, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_CRC); -} - -/** - * @brief Encode a extended_sys_state struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param extended_sys_state C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_extended_sys_state_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_extended_sys_state_t* extended_sys_state) -{ - return mavlink_msg_extended_sys_state_pack(system_id, component_id, msg, extended_sys_state->vtol_state, extended_sys_state->landed_state); -} - -/** - * @brief Encode a extended_sys_state struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param extended_sys_state C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_extended_sys_state_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_extended_sys_state_t* extended_sys_state) -{ - return mavlink_msg_extended_sys_state_pack_chan(system_id, component_id, chan, msg, extended_sys_state->vtol_state, extended_sys_state->landed_state); -} - -/** - * @brief Send a extended_sys_state message - * @param chan MAVLink channel to send the message - * - * @param vtol_state The VTOL state if applicable. Is set to MAV_VTOL_STATE_UNDEFINED if UAV is not in VTOL configuration. - * @param landed_state The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_extended_sys_state_send(mavlink_channel_t chan, uint8_t vtol_state, uint8_t landed_state) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_EXTENDED_SYS_STATE_LEN]; - _mav_put_uint8_t(buf, 0, vtol_state); - _mav_put_uint8_t(buf, 1, landed_state); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_EXTENDED_SYS_STATE, buf, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_MIN_LEN, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_LEN, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_CRC); -#else - mavlink_extended_sys_state_t packet; - packet.vtol_state = vtol_state; - packet.landed_state = landed_state; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_EXTENDED_SYS_STATE, (const char *)&packet, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_MIN_LEN, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_LEN, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_CRC); -#endif -} - -/** - * @brief Send a extended_sys_state message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_extended_sys_state_send_struct(mavlink_channel_t chan, const mavlink_extended_sys_state_t* extended_sys_state) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_extended_sys_state_send(chan, extended_sys_state->vtol_state, extended_sys_state->landed_state); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_EXTENDED_SYS_STATE, (const char *)extended_sys_state, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_MIN_LEN, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_LEN, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_CRC); -#endif -} - -#if MAVLINK_MSG_ID_EXTENDED_SYS_STATE_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_extended_sys_state_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t vtol_state, uint8_t landed_state) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint8_t(buf, 0, vtol_state); - _mav_put_uint8_t(buf, 1, landed_state); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_EXTENDED_SYS_STATE, buf, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_MIN_LEN, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_LEN, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_CRC); -#else - mavlink_extended_sys_state_t *packet = (mavlink_extended_sys_state_t *)msgbuf; - packet->vtol_state = vtol_state; - packet->landed_state = landed_state; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_EXTENDED_SYS_STATE, (const char *)packet, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_MIN_LEN, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_LEN, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_CRC); -#endif -} -#endif - -#endif - -// MESSAGE EXTENDED_SYS_STATE UNPACKING - - -/** - * @brief Get field vtol_state from extended_sys_state message - * - * @return The VTOL state if applicable. Is set to MAV_VTOL_STATE_UNDEFINED if UAV is not in VTOL configuration. - */ -static inline uint8_t mavlink_msg_extended_sys_state_get_vtol_state(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 0); -} - -/** - * @brief Get field landed_state from extended_sys_state message - * - * @return The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown. - */ -static inline uint8_t mavlink_msg_extended_sys_state_get_landed_state(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 1); -} - -/** - * @brief Decode a extended_sys_state message into a struct - * - * @param msg The message to decode - * @param extended_sys_state C-struct to decode the message contents into - */ -static inline void mavlink_msg_extended_sys_state_decode(const mavlink_message_t* msg, mavlink_extended_sys_state_t* extended_sys_state) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - extended_sys_state->vtol_state = mavlink_msg_extended_sys_state_get_vtol_state(msg); - extended_sys_state->landed_state = mavlink_msg_extended_sys_state_get_landed_state(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_EXTENDED_SYS_STATE_LEN? msg->len : MAVLINK_MSG_ID_EXTENDED_SYS_STATE_LEN; - memset(extended_sys_state, 0, MAVLINK_MSG_ID_EXTENDED_SYS_STATE_LEN); - memcpy(extended_sys_state, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_fence_status.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_fence_status.h deleted file mode 100644 index 98b442aa..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_fence_status.h +++ /dev/null @@ -1,313 +0,0 @@ -#pragma once -// MESSAGE FENCE_STATUS PACKING - -#define MAVLINK_MSG_ID_FENCE_STATUS 162 - - -typedef struct __mavlink_fence_status_t { - uint32_t breach_time; /*< [ms] Time (since boot) of last breach.*/ - uint16_t breach_count; /*< Number of fence breaches.*/ - uint8_t breach_status; /*< Breach status (0 if currently inside fence, 1 if outside).*/ - uint8_t breach_type; /*< Last breach type.*/ - uint8_t breach_mitigation; /*< Active action to prevent fence breach*/ -} mavlink_fence_status_t; - -#define MAVLINK_MSG_ID_FENCE_STATUS_LEN 9 -#define MAVLINK_MSG_ID_FENCE_STATUS_MIN_LEN 8 -#define MAVLINK_MSG_ID_162_LEN 9 -#define MAVLINK_MSG_ID_162_MIN_LEN 8 - -#define MAVLINK_MSG_ID_FENCE_STATUS_CRC 189 -#define MAVLINK_MSG_ID_162_CRC 189 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_FENCE_STATUS { \ - 162, \ - "FENCE_STATUS", \ - 5, \ - { { "breach_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_fence_status_t, breach_status) }, \ - { "breach_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_fence_status_t, breach_count) }, \ - { "breach_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_fence_status_t, breach_type) }, \ - { "breach_time", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_fence_status_t, breach_time) }, \ - { "breach_mitigation", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_fence_status_t, breach_mitigation) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_FENCE_STATUS { \ - "FENCE_STATUS", \ - 5, \ - { { "breach_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_fence_status_t, breach_status) }, \ - { "breach_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_fence_status_t, breach_count) }, \ - { "breach_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_fence_status_t, breach_type) }, \ - { "breach_time", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_fence_status_t, breach_time) }, \ - { "breach_mitigation", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_fence_status_t, breach_mitigation) }, \ - } \ -} -#endif - -/** - * @brief Pack a fence_status message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param breach_status Breach status (0 if currently inside fence, 1 if outside). - * @param breach_count Number of fence breaches. - * @param breach_type Last breach type. - * @param breach_time [ms] Time (since boot) of last breach. - * @param breach_mitigation Active action to prevent fence breach - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_fence_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t breach_status, uint16_t breach_count, uint8_t breach_type, uint32_t breach_time, uint8_t breach_mitigation) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_FENCE_STATUS_LEN]; - _mav_put_uint32_t(buf, 0, breach_time); - _mav_put_uint16_t(buf, 4, breach_count); - _mav_put_uint8_t(buf, 6, breach_status); - _mav_put_uint8_t(buf, 7, breach_type); - _mav_put_uint8_t(buf, 8, breach_mitigation); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FENCE_STATUS_LEN); -#else - mavlink_fence_status_t packet; - packet.breach_time = breach_time; - packet.breach_count = breach_count; - packet.breach_status = breach_status; - packet.breach_type = breach_type; - packet.breach_mitigation = breach_mitigation; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FENCE_STATUS_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_FENCE_STATUS; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_FENCE_STATUS_MIN_LEN, MAVLINK_MSG_ID_FENCE_STATUS_LEN, MAVLINK_MSG_ID_FENCE_STATUS_CRC); -} - -/** - * @brief Pack a fence_status message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param breach_status Breach status (0 if currently inside fence, 1 if outside). - * @param breach_count Number of fence breaches. - * @param breach_type Last breach type. - * @param breach_time [ms] Time (since boot) of last breach. - * @param breach_mitigation Active action to prevent fence breach - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_fence_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t breach_status,uint16_t breach_count,uint8_t breach_type,uint32_t breach_time,uint8_t breach_mitigation) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_FENCE_STATUS_LEN]; - _mav_put_uint32_t(buf, 0, breach_time); - _mav_put_uint16_t(buf, 4, breach_count); - _mav_put_uint8_t(buf, 6, breach_status); - _mav_put_uint8_t(buf, 7, breach_type); - _mav_put_uint8_t(buf, 8, breach_mitigation); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FENCE_STATUS_LEN); -#else - mavlink_fence_status_t packet; - packet.breach_time = breach_time; - packet.breach_count = breach_count; - packet.breach_status = breach_status; - packet.breach_type = breach_type; - packet.breach_mitigation = breach_mitigation; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FENCE_STATUS_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_FENCE_STATUS; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_FENCE_STATUS_MIN_LEN, MAVLINK_MSG_ID_FENCE_STATUS_LEN, MAVLINK_MSG_ID_FENCE_STATUS_CRC); -} - -/** - * @brief Encode a fence_status struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param fence_status C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_fence_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_fence_status_t* fence_status) -{ - return mavlink_msg_fence_status_pack(system_id, component_id, msg, fence_status->breach_status, fence_status->breach_count, fence_status->breach_type, fence_status->breach_time, fence_status->breach_mitigation); -} - -/** - * @brief Encode a fence_status struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param fence_status C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_fence_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_fence_status_t* fence_status) -{ - return mavlink_msg_fence_status_pack_chan(system_id, component_id, chan, msg, fence_status->breach_status, fence_status->breach_count, fence_status->breach_type, fence_status->breach_time, fence_status->breach_mitigation); -} - -/** - * @brief Send a fence_status message - * @param chan MAVLink channel to send the message - * - * @param breach_status Breach status (0 if currently inside fence, 1 if outside). - * @param breach_count Number of fence breaches. - * @param breach_type Last breach type. - * @param breach_time [ms] Time (since boot) of last breach. - * @param breach_mitigation Active action to prevent fence breach - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_fence_status_send(mavlink_channel_t chan, uint8_t breach_status, uint16_t breach_count, uint8_t breach_type, uint32_t breach_time, uint8_t breach_mitigation) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_FENCE_STATUS_LEN]; - _mav_put_uint32_t(buf, 0, breach_time); - _mav_put_uint16_t(buf, 4, breach_count); - _mav_put_uint8_t(buf, 6, breach_status); - _mav_put_uint8_t(buf, 7, breach_type); - _mav_put_uint8_t(buf, 8, breach_mitigation); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_STATUS, buf, MAVLINK_MSG_ID_FENCE_STATUS_MIN_LEN, MAVLINK_MSG_ID_FENCE_STATUS_LEN, MAVLINK_MSG_ID_FENCE_STATUS_CRC); -#else - mavlink_fence_status_t packet; - packet.breach_time = breach_time; - packet.breach_count = breach_count; - packet.breach_status = breach_status; - packet.breach_type = breach_type; - packet.breach_mitigation = breach_mitigation; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_STATUS, (const char *)&packet, MAVLINK_MSG_ID_FENCE_STATUS_MIN_LEN, MAVLINK_MSG_ID_FENCE_STATUS_LEN, MAVLINK_MSG_ID_FENCE_STATUS_CRC); -#endif -} - -/** - * @brief Send a fence_status message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_fence_status_send_struct(mavlink_channel_t chan, const mavlink_fence_status_t* fence_status) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_fence_status_send(chan, fence_status->breach_status, fence_status->breach_count, fence_status->breach_type, fence_status->breach_time, fence_status->breach_mitigation); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_STATUS, (const char *)fence_status, MAVLINK_MSG_ID_FENCE_STATUS_MIN_LEN, MAVLINK_MSG_ID_FENCE_STATUS_LEN, MAVLINK_MSG_ID_FENCE_STATUS_CRC); -#endif -} - -#if MAVLINK_MSG_ID_FENCE_STATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_fence_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t breach_status, uint16_t breach_count, uint8_t breach_type, uint32_t breach_time, uint8_t breach_mitigation) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, breach_time); - _mav_put_uint16_t(buf, 4, breach_count); - _mav_put_uint8_t(buf, 6, breach_status); - _mav_put_uint8_t(buf, 7, breach_type); - _mav_put_uint8_t(buf, 8, breach_mitigation); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_STATUS, buf, MAVLINK_MSG_ID_FENCE_STATUS_MIN_LEN, MAVLINK_MSG_ID_FENCE_STATUS_LEN, MAVLINK_MSG_ID_FENCE_STATUS_CRC); -#else - mavlink_fence_status_t *packet = (mavlink_fence_status_t *)msgbuf; - packet->breach_time = breach_time; - packet->breach_count = breach_count; - packet->breach_status = breach_status; - packet->breach_type = breach_type; - packet->breach_mitigation = breach_mitigation; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_STATUS, (const char *)packet, MAVLINK_MSG_ID_FENCE_STATUS_MIN_LEN, MAVLINK_MSG_ID_FENCE_STATUS_LEN, MAVLINK_MSG_ID_FENCE_STATUS_CRC); -#endif -} -#endif - -#endif - -// MESSAGE FENCE_STATUS UNPACKING - - -/** - * @brief Get field breach_status from fence_status message - * - * @return Breach status (0 if currently inside fence, 1 if outside). - */ -static inline uint8_t mavlink_msg_fence_status_get_breach_status(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 6); -} - -/** - * @brief Get field breach_count from fence_status message - * - * @return Number of fence breaches. - */ -static inline uint16_t mavlink_msg_fence_status_get_breach_count(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 4); -} - -/** - * @brief Get field breach_type from fence_status message - * - * @return Last breach type. - */ -static inline uint8_t mavlink_msg_fence_status_get_breach_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 7); -} - -/** - * @brief Get field breach_time from fence_status message - * - * @return [ms] Time (since boot) of last breach. - */ -static inline uint32_t mavlink_msg_fence_status_get_breach_time(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field breach_mitigation from fence_status message - * - * @return Active action to prevent fence breach - */ -static inline uint8_t mavlink_msg_fence_status_get_breach_mitigation(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 8); -} - -/** - * @brief Decode a fence_status message into a struct - * - * @param msg The message to decode - * @param fence_status C-struct to decode the message contents into - */ -static inline void mavlink_msg_fence_status_decode(const mavlink_message_t* msg, mavlink_fence_status_t* fence_status) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - fence_status->breach_time = mavlink_msg_fence_status_get_breach_time(msg); - fence_status->breach_count = mavlink_msg_fence_status_get_breach_count(msg); - fence_status->breach_status = mavlink_msg_fence_status_get_breach_status(msg); - fence_status->breach_type = mavlink_msg_fence_status_get_breach_type(msg); - fence_status->breach_mitigation = mavlink_msg_fence_status_get_breach_mitigation(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_FENCE_STATUS_LEN? msg->len : MAVLINK_MSG_ID_FENCE_STATUS_LEN; - memset(fence_status, 0, MAVLINK_MSG_ID_FENCE_STATUS_LEN); - memcpy(fence_status, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_file_transfer_protocol.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_file_transfer_protocol.h deleted file mode 100644 index 68d5a54e..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_file_transfer_protocol.h +++ /dev/null @@ -1,280 +0,0 @@ -#pragma once -// MESSAGE FILE_TRANSFER_PROTOCOL PACKING - -#define MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL 110 - - -typedef struct __mavlink_file_transfer_protocol_t { - uint8_t target_network; /*< Network ID (0 for broadcast)*/ - uint8_t target_system; /*< System ID (0 for broadcast)*/ - uint8_t target_component; /*< Component ID (0 for broadcast)*/ - uint8_t payload[251]; /*< Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The content/format of this block is defined in https://mavlink.io/en/services/ftp.html.*/ -} mavlink_file_transfer_protocol_t; - -#define MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN 254 -#define MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_MIN_LEN 254 -#define MAVLINK_MSG_ID_110_LEN 254 -#define MAVLINK_MSG_ID_110_MIN_LEN 254 - -#define MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_CRC 84 -#define MAVLINK_MSG_ID_110_CRC 84 - -#define MAVLINK_MSG_FILE_TRANSFER_PROTOCOL_FIELD_PAYLOAD_LEN 251 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_FILE_TRANSFER_PROTOCOL { \ - 110, \ - "FILE_TRANSFER_PROTOCOL", \ - 4, \ - { { "target_network", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_file_transfer_protocol_t, target_network) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_file_transfer_protocol_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_file_transfer_protocol_t, target_component) }, \ - { "payload", NULL, MAVLINK_TYPE_UINT8_T, 251, 3, offsetof(mavlink_file_transfer_protocol_t, payload) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_FILE_TRANSFER_PROTOCOL { \ - "FILE_TRANSFER_PROTOCOL", \ - 4, \ - { { "target_network", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_file_transfer_protocol_t, target_network) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_file_transfer_protocol_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_file_transfer_protocol_t, target_component) }, \ - { "payload", NULL, MAVLINK_TYPE_UINT8_T, 251, 3, offsetof(mavlink_file_transfer_protocol_t, payload) }, \ - } \ -} -#endif - -/** - * @brief Pack a file_transfer_protocol message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_network Network ID (0 for broadcast) - * @param target_system System ID (0 for broadcast) - * @param target_component Component ID (0 for broadcast) - * @param payload Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The content/format of this block is defined in https://mavlink.io/en/services/ftp.html. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_file_transfer_protocol_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_network, uint8_t target_system, uint8_t target_component, const uint8_t *payload) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN]; - _mav_put_uint8_t(buf, 0, target_network); - _mav_put_uint8_t(buf, 1, target_system); - _mav_put_uint8_t(buf, 2, target_component); - _mav_put_uint8_t_array(buf, 3, payload, 251); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN); -#else - mavlink_file_transfer_protocol_t packet; - packet.target_network = target_network; - packet.target_system = target_system; - packet.target_component = target_component; - mav_array_memcpy(packet.payload, payload, sizeof(uint8_t)*251); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_MIN_LEN, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_CRC); -} - -/** - * @brief Pack a file_transfer_protocol message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_network Network ID (0 for broadcast) - * @param target_system System ID (0 for broadcast) - * @param target_component Component ID (0 for broadcast) - * @param payload Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The content/format of this block is defined in https://mavlink.io/en/services/ftp.html. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_file_transfer_protocol_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_network,uint8_t target_system,uint8_t target_component,const uint8_t *payload) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN]; - _mav_put_uint8_t(buf, 0, target_network); - _mav_put_uint8_t(buf, 1, target_system); - _mav_put_uint8_t(buf, 2, target_component); - _mav_put_uint8_t_array(buf, 3, payload, 251); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN); -#else - mavlink_file_transfer_protocol_t packet; - packet.target_network = target_network; - packet.target_system = target_system; - packet.target_component = target_component; - mav_array_memcpy(packet.payload, payload, sizeof(uint8_t)*251); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_MIN_LEN, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_CRC); -} - -/** - * @brief Encode a file_transfer_protocol struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param file_transfer_protocol C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_file_transfer_protocol_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_file_transfer_protocol_t* file_transfer_protocol) -{ - return mavlink_msg_file_transfer_protocol_pack(system_id, component_id, msg, file_transfer_protocol->target_network, file_transfer_protocol->target_system, file_transfer_protocol->target_component, file_transfer_protocol->payload); -} - -/** - * @brief Encode a file_transfer_protocol struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param file_transfer_protocol C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_file_transfer_protocol_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_file_transfer_protocol_t* file_transfer_protocol) -{ - return mavlink_msg_file_transfer_protocol_pack_chan(system_id, component_id, chan, msg, file_transfer_protocol->target_network, file_transfer_protocol->target_system, file_transfer_protocol->target_component, file_transfer_protocol->payload); -} - -/** - * @brief Send a file_transfer_protocol message - * @param chan MAVLink channel to send the message - * - * @param target_network Network ID (0 for broadcast) - * @param target_system System ID (0 for broadcast) - * @param target_component Component ID (0 for broadcast) - * @param payload Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The content/format of this block is defined in https://mavlink.io/en/services/ftp.html. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_file_transfer_protocol_send(mavlink_channel_t chan, uint8_t target_network, uint8_t target_system, uint8_t target_component, const uint8_t *payload) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN]; - _mav_put_uint8_t(buf, 0, target_network); - _mav_put_uint8_t(buf, 1, target_system); - _mav_put_uint8_t(buf, 2, target_component); - _mav_put_uint8_t_array(buf, 3, payload, 251); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL, buf, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_MIN_LEN, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_CRC); -#else - mavlink_file_transfer_protocol_t packet; - packet.target_network = target_network; - packet.target_system = target_system; - packet.target_component = target_component; - mav_array_memcpy(packet.payload, payload, sizeof(uint8_t)*251); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL, (const char *)&packet, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_MIN_LEN, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_CRC); -#endif -} - -/** - * @brief Send a file_transfer_protocol message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_file_transfer_protocol_send_struct(mavlink_channel_t chan, const mavlink_file_transfer_protocol_t* file_transfer_protocol) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_file_transfer_protocol_send(chan, file_transfer_protocol->target_network, file_transfer_protocol->target_system, file_transfer_protocol->target_component, file_transfer_protocol->payload); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL, (const char *)file_transfer_protocol, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_MIN_LEN, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_CRC); -#endif -} - -#if MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_file_transfer_protocol_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_network, uint8_t target_system, uint8_t target_component, const uint8_t *payload) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint8_t(buf, 0, target_network); - _mav_put_uint8_t(buf, 1, target_system); - _mav_put_uint8_t(buf, 2, target_component); - _mav_put_uint8_t_array(buf, 3, payload, 251); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL, buf, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_MIN_LEN, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_CRC); -#else - mavlink_file_transfer_protocol_t *packet = (mavlink_file_transfer_protocol_t *)msgbuf; - packet->target_network = target_network; - packet->target_system = target_system; - packet->target_component = target_component; - mav_array_memcpy(packet->payload, payload, sizeof(uint8_t)*251); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL, (const char *)packet, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_MIN_LEN, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_CRC); -#endif -} -#endif - -#endif - -// MESSAGE FILE_TRANSFER_PROTOCOL UNPACKING - - -/** - * @brief Get field target_network from file_transfer_protocol message - * - * @return Network ID (0 for broadcast) - */ -static inline uint8_t mavlink_msg_file_transfer_protocol_get_target_network(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 0); -} - -/** - * @brief Get field target_system from file_transfer_protocol message - * - * @return System ID (0 for broadcast) - */ -static inline uint8_t mavlink_msg_file_transfer_protocol_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 1); -} - -/** - * @brief Get field target_component from file_transfer_protocol message - * - * @return Component ID (0 for broadcast) - */ -static inline uint8_t mavlink_msg_file_transfer_protocol_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 2); -} - -/** - * @brief Get field payload from file_transfer_protocol message - * - * @return Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The content/format of this block is defined in https://mavlink.io/en/services/ftp.html. - */ -static inline uint16_t mavlink_msg_file_transfer_protocol_get_payload(const mavlink_message_t* msg, uint8_t *payload) -{ - return _MAV_RETURN_uint8_t_array(msg, payload, 251, 3); -} - -/** - * @brief Decode a file_transfer_protocol message into a struct - * - * @param msg The message to decode - * @param file_transfer_protocol C-struct to decode the message contents into - */ -static inline void mavlink_msg_file_transfer_protocol_decode(const mavlink_message_t* msg, mavlink_file_transfer_protocol_t* file_transfer_protocol) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - file_transfer_protocol->target_network = mavlink_msg_file_transfer_protocol_get_target_network(msg); - file_transfer_protocol->target_system = mavlink_msg_file_transfer_protocol_get_target_system(msg); - file_transfer_protocol->target_component = mavlink_msg_file_transfer_protocol_get_target_component(msg); - mavlink_msg_file_transfer_protocol_get_payload(msg, file_transfer_protocol->payload); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN? msg->len : MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN; - memset(file_transfer_protocol, 0, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN); - memcpy(file_transfer_protocol, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_flight_information.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_flight_information.h deleted file mode 100644 index a0cd15c2..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_flight_information.h +++ /dev/null @@ -1,288 +0,0 @@ -#pragma once -// MESSAGE FLIGHT_INFORMATION PACKING - -#define MAVLINK_MSG_ID_FLIGHT_INFORMATION 264 - - -typedef struct __mavlink_flight_information_t { - uint64_t arming_time_utc; /*< [us] Timestamp at arming (time since UNIX epoch) in UTC, 0 for unknown*/ - uint64_t takeoff_time_utc; /*< [us] Timestamp at takeoff (time since UNIX epoch) in UTC, 0 for unknown*/ - uint64_t flight_uuid; /*< Universally unique identifier (UUID) of flight, should correspond to name of log files*/ - uint32_t time_boot_ms; /*< [ms] Timestamp (time since system boot).*/ -} mavlink_flight_information_t; - -#define MAVLINK_MSG_ID_FLIGHT_INFORMATION_LEN 28 -#define MAVLINK_MSG_ID_FLIGHT_INFORMATION_MIN_LEN 28 -#define MAVLINK_MSG_ID_264_LEN 28 -#define MAVLINK_MSG_ID_264_MIN_LEN 28 - -#define MAVLINK_MSG_ID_FLIGHT_INFORMATION_CRC 49 -#define MAVLINK_MSG_ID_264_CRC 49 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_FLIGHT_INFORMATION { \ - 264, \ - "FLIGHT_INFORMATION", \ - 4, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 24, offsetof(mavlink_flight_information_t, time_boot_ms) }, \ - { "arming_time_utc", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_flight_information_t, arming_time_utc) }, \ - { "takeoff_time_utc", NULL, MAVLINK_TYPE_UINT64_T, 0, 8, offsetof(mavlink_flight_information_t, takeoff_time_utc) }, \ - { "flight_uuid", NULL, MAVLINK_TYPE_UINT64_T, 0, 16, offsetof(mavlink_flight_information_t, flight_uuid) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_FLIGHT_INFORMATION { \ - "FLIGHT_INFORMATION", \ - 4, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 24, offsetof(mavlink_flight_information_t, time_boot_ms) }, \ - { "arming_time_utc", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_flight_information_t, arming_time_utc) }, \ - { "takeoff_time_utc", NULL, MAVLINK_TYPE_UINT64_T, 0, 8, offsetof(mavlink_flight_information_t, takeoff_time_utc) }, \ - { "flight_uuid", NULL, MAVLINK_TYPE_UINT64_T, 0, 16, offsetof(mavlink_flight_information_t, flight_uuid) }, \ - } \ -} -#endif - -/** - * @brief Pack a flight_information message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param time_boot_ms [ms] Timestamp (time since system boot). - * @param arming_time_utc [us] Timestamp at arming (time since UNIX epoch) in UTC, 0 for unknown - * @param takeoff_time_utc [us] Timestamp at takeoff (time since UNIX epoch) in UTC, 0 for unknown - * @param flight_uuid Universally unique identifier (UUID) of flight, should correspond to name of log files - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_flight_information_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint32_t time_boot_ms, uint64_t arming_time_utc, uint64_t takeoff_time_utc, uint64_t flight_uuid) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_FLIGHT_INFORMATION_LEN]; - _mav_put_uint64_t(buf, 0, arming_time_utc); - _mav_put_uint64_t(buf, 8, takeoff_time_utc); - _mav_put_uint64_t(buf, 16, flight_uuid); - _mav_put_uint32_t(buf, 24, time_boot_ms); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FLIGHT_INFORMATION_LEN); -#else - mavlink_flight_information_t packet; - packet.arming_time_utc = arming_time_utc; - packet.takeoff_time_utc = takeoff_time_utc; - packet.flight_uuid = flight_uuid; - packet.time_boot_ms = time_boot_ms; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FLIGHT_INFORMATION_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_FLIGHT_INFORMATION; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_FLIGHT_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_FLIGHT_INFORMATION_LEN, MAVLINK_MSG_ID_FLIGHT_INFORMATION_CRC); -} - -/** - * @brief Pack a flight_information message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_boot_ms [ms] Timestamp (time since system boot). - * @param arming_time_utc [us] Timestamp at arming (time since UNIX epoch) in UTC, 0 for unknown - * @param takeoff_time_utc [us] Timestamp at takeoff (time since UNIX epoch) in UTC, 0 for unknown - * @param flight_uuid Universally unique identifier (UUID) of flight, should correspond to name of log files - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_flight_information_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint32_t time_boot_ms,uint64_t arming_time_utc,uint64_t takeoff_time_utc,uint64_t flight_uuid) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_FLIGHT_INFORMATION_LEN]; - _mav_put_uint64_t(buf, 0, arming_time_utc); - _mav_put_uint64_t(buf, 8, takeoff_time_utc); - _mav_put_uint64_t(buf, 16, flight_uuid); - _mav_put_uint32_t(buf, 24, time_boot_ms); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FLIGHT_INFORMATION_LEN); -#else - mavlink_flight_information_t packet; - packet.arming_time_utc = arming_time_utc; - packet.takeoff_time_utc = takeoff_time_utc; - packet.flight_uuid = flight_uuid; - packet.time_boot_ms = time_boot_ms; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FLIGHT_INFORMATION_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_FLIGHT_INFORMATION; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_FLIGHT_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_FLIGHT_INFORMATION_LEN, MAVLINK_MSG_ID_FLIGHT_INFORMATION_CRC); -} - -/** - * @brief Encode a flight_information struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param flight_information C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_flight_information_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_flight_information_t* flight_information) -{ - return mavlink_msg_flight_information_pack(system_id, component_id, msg, flight_information->time_boot_ms, flight_information->arming_time_utc, flight_information->takeoff_time_utc, flight_information->flight_uuid); -} - -/** - * @brief Encode a flight_information struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param flight_information C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_flight_information_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_flight_information_t* flight_information) -{ - return mavlink_msg_flight_information_pack_chan(system_id, component_id, chan, msg, flight_information->time_boot_ms, flight_information->arming_time_utc, flight_information->takeoff_time_utc, flight_information->flight_uuid); -} - -/** - * @brief Send a flight_information message - * @param chan MAVLink channel to send the message - * - * @param time_boot_ms [ms] Timestamp (time since system boot). - * @param arming_time_utc [us] Timestamp at arming (time since UNIX epoch) in UTC, 0 for unknown - * @param takeoff_time_utc [us] Timestamp at takeoff (time since UNIX epoch) in UTC, 0 for unknown - * @param flight_uuid Universally unique identifier (UUID) of flight, should correspond to name of log files - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_flight_information_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint64_t arming_time_utc, uint64_t takeoff_time_utc, uint64_t flight_uuid) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_FLIGHT_INFORMATION_LEN]; - _mav_put_uint64_t(buf, 0, arming_time_utc); - _mav_put_uint64_t(buf, 8, takeoff_time_utc); - _mav_put_uint64_t(buf, 16, flight_uuid); - _mav_put_uint32_t(buf, 24, time_boot_ms); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLIGHT_INFORMATION, buf, MAVLINK_MSG_ID_FLIGHT_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_FLIGHT_INFORMATION_LEN, MAVLINK_MSG_ID_FLIGHT_INFORMATION_CRC); -#else - mavlink_flight_information_t packet; - packet.arming_time_utc = arming_time_utc; - packet.takeoff_time_utc = takeoff_time_utc; - packet.flight_uuid = flight_uuid; - packet.time_boot_ms = time_boot_ms; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLIGHT_INFORMATION, (const char *)&packet, MAVLINK_MSG_ID_FLIGHT_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_FLIGHT_INFORMATION_LEN, MAVLINK_MSG_ID_FLIGHT_INFORMATION_CRC); -#endif -} - -/** - * @brief Send a flight_information message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_flight_information_send_struct(mavlink_channel_t chan, const mavlink_flight_information_t* flight_information) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_flight_information_send(chan, flight_information->time_boot_ms, flight_information->arming_time_utc, flight_information->takeoff_time_utc, flight_information->flight_uuid); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLIGHT_INFORMATION, (const char *)flight_information, MAVLINK_MSG_ID_FLIGHT_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_FLIGHT_INFORMATION_LEN, MAVLINK_MSG_ID_FLIGHT_INFORMATION_CRC); -#endif -} - -#if MAVLINK_MSG_ID_FLIGHT_INFORMATION_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_flight_information_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint64_t arming_time_utc, uint64_t takeoff_time_utc, uint64_t flight_uuid) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, arming_time_utc); - _mav_put_uint64_t(buf, 8, takeoff_time_utc); - _mav_put_uint64_t(buf, 16, flight_uuid); - _mav_put_uint32_t(buf, 24, time_boot_ms); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLIGHT_INFORMATION, buf, MAVLINK_MSG_ID_FLIGHT_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_FLIGHT_INFORMATION_LEN, MAVLINK_MSG_ID_FLIGHT_INFORMATION_CRC); -#else - mavlink_flight_information_t *packet = (mavlink_flight_information_t *)msgbuf; - packet->arming_time_utc = arming_time_utc; - packet->takeoff_time_utc = takeoff_time_utc; - packet->flight_uuid = flight_uuid; - packet->time_boot_ms = time_boot_ms; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLIGHT_INFORMATION, (const char *)packet, MAVLINK_MSG_ID_FLIGHT_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_FLIGHT_INFORMATION_LEN, MAVLINK_MSG_ID_FLIGHT_INFORMATION_CRC); -#endif -} -#endif - -#endif - -// MESSAGE FLIGHT_INFORMATION UNPACKING - - -/** - * @brief Get field time_boot_ms from flight_information message - * - * @return [ms] Timestamp (time since system boot). - */ -static inline uint32_t mavlink_msg_flight_information_get_time_boot_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 24); -} - -/** - * @brief Get field arming_time_utc from flight_information message - * - * @return [us] Timestamp at arming (time since UNIX epoch) in UTC, 0 for unknown - */ -static inline uint64_t mavlink_msg_flight_information_get_arming_time_utc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field takeoff_time_utc from flight_information message - * - * @return [us] Timestamp at takeoff (time since UNIX epoch) in UTC, 0 for unknown - */ -static inline uint64_t mavlink_msg_flight_information_get_takeoff_time_utc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 8); -} - -/** - * @brief Get field flight_uuid from flight_information message - * - * @return Universally unique identifier (UUID) of flight, should correspond to name of log files - */ -static inline uint64_t mavlink_msg_flight_information_get_flight_uuid(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 16); -} - -/** - * @brief Decode a flight_information message into a struct - * - * @param msg The message to decode - * @param flight_information C-struct to decode the message contents into - */ -static inline void mavlink_msg_flight_information_decode(const mavlink_message_t* msg, mavlink_flight_information_t* flight_information) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - flight_information->arming_time_utc = mavlink_msg_flight_information_get_arming_time_utc(msg); - flight_information->takeoff_time_utc = mavlink_msg_flight_information_get_takeoff_time_utc(msg); - flight_information->flight_uuid = mavlink_msg_flight_information_get_flight_uuid(msg); - flight_information->time_boot_ms = mavlink_msg_flight_information_get_time_boot_ms(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_FLIGHT_INFORMATION_LEN? msg->len : MAVLINK_MSG_ID_FLIGHT_INFORMATION_LEN; - memset(flight_information, 0, MAVLINK_MSG_ID_FLIGHT_INFORMATION_LEN); - memcpy(flight_information, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_follow_target.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_follow_target.h deleted file mode 100644 index 1c854728..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_follow_target.h +++ /dev/null @@ -1,459 +0,0 @@ -#pragma once -// MESSAGE FOLLOW_TARGET PACKING - -#define MAVLINK_MSG_ID_FOLLOW_TARGET 144 - - -typedef struct __mavlink_follow_target_t { - uint64_t timestamp; /*< [ms] Timestamp (time since system boot).*/ - uint64_t custom_state; /*< button states or switches of a tracker device*/ - int32_t lat; /*< [degE7] Latitude (WGS84)*/ - int32_t lon; /*< [degE7] Longitude (WGS84)*/ - float alt; /*< [m] Altitude (MSL)*/ - float vel[3]; /*< [m/s] target velocity (0,0,0) for unknown*/ - float acc[3]; /*< [m/s/s] linear target acceleration (0,0,0) for unknown*/ - float attitude_q[4]; /*< (0 0 0 0 for unknown)*/ - float rates[3]; /*< (0 0 0 for unknown)*/ - float position_cov[3]; /*< eph epv*/ - uint8_t est_capabilities; /*< bit positions for tracker reporting capabilities (POS = 0, VEL = 1, ACCEL = 2, ATT + RATES = 3)*/ -} mavlink_follow_target_t; - -#define MAVLINK_MSG_ID_FOLLOW_TARGET_LEN 93 -#define MAVLINK_MSG_ID_FOLLOW_TARGET_MIN_LEN 93 -#define MAVLINK_MSG_ID_144_LEN 93 -#define MAVLINK_MSG_ID_144_MIN_LEN 93 - -#define MAVLINK_MSG_ID_FOLLOW_TARGET_CRC 127 -#define MAVLINK_MSG_ID_144_CRC 127 - -#define MAVLINK_MSG_FOLLOW_TARGET_FIELD_VEL_LEN 3 -#define MAVLINK_MSG_FOLLOW_TARGET_FIELD_ACC_LEN 3 -#define MAVLINK_MSG_FOLLOW_TARGET_FIELD_ATTITUDE_Q_LEN 4 -#define MAVLINK_MSG_FOLLOW_TARGET_FIELD_RATES_LEN 3 -#define MAVLINK_MSG_FOLLOW_TARGET_FIELD_POSITION_COV_LEN 3 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_FOLLOW_TARGET { \ - 144, \ - "FOLLOW_TARGET", \ - 11, \ - { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_follow_target_t, timestamp) }, \ - { "est_capabilities", NULL, MAVLINK_TYPE_UINT8_T, 0, 92, offsetof(mavlink_follow_target_t, est_capabilities) }, \ - { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_follow_target_t, lat) }, \ - { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 20, offsetof(mavlink_follow_target_t, lon) }, \ - { "alt", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_follow_target_t, alt) }, \ - { "vel", NULL, MAVLINK_TYPE_FLOAT, 3, 28, offsetof(mavlink_follow_target_t, vel) }, \ - { "acc", NULL, MAVLINK_TYPE_FLOAT, 3, 40, offsetof(mavlink_follow_target_t, acc) }, \ - { "attitude_q", NULL, MAVLINK_TYPE_FLOAT, 4, 52, offsetof(mavlink_follow_target_t, attitude_q) }, \ - { "rates", NULL, MAVLINK_TYPE_FLOAT, 3, 68, offsetof(mavlink_follow_target_t, rates) }, \ - { "position_cov", NULL, MAVLINK_TYPE_FLOAT, 3, 80, offsetof(mavlink_follow_target_t, position_cov) }, \ - { "custom_state", NULL, MAVLINK_TYPE_UINT64_T, 0, 8, offsetof(mavlink_follow_target_t, custom_state) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_FOLLOW_TARGET { \ - "FOLLOW_TARGET", \ - 11, \ - { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_follow_target_t, timestamp) }, \ - { "est_capabilities", NULL, MAVLINK_TYPE_UINT8_T, 0, 92, offsetof(mavlink_follow_target_t, est_capabilities) }, \ - { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_follow_target_t, lat) }, \ - { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 20, offsetof(mavlink_follow_target_t, lon) }, \ - { "alt", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_follow_target_t, alt) }, \ - { "vel", NULL, MAVLINK_TYPE_FLOAT, 3, 28, offsetof(mavlink_follow_target_t, vel) }, \ - { "acc", NULL, MAVLINK_TYPE_FLOAT, 3, 40, offsetof(mavlink_follow_target_t, acc) }, \ - { "attitude_q", NULL, MAVLINK_TYPE_FLOAT, 4, 52, offsetof(mavlink_follow_target_t, attitude_q) }, \ - { "rates", NULL, MAVLINK_TYPE_FLOAT, 3, 68, offsetof(mavlink_follow_target_t, rates) }, \ - { "position_cov", NULL, MAVLINK_TYPE_FLOAT, 3, 80, offsetof(mavlink_follow_target_t, position_cov) }, \ - { "custom_state", NULL, MAVLINK_TYPE_UINT64_T, 0, 8, offsetof(mavlink_follow_target_t, custom_state) }, \ - } \ -} -#endif - -/** - * @brief Pack a follow_target message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param timestamp [ms] Timestamp (time since system boot). - * @param est_capabilities bit positions for tracker reporting capabilities (POS = 0, VEL = 1, ACCEL = 2, ATT + RATES = 3) - * @param lat [degE7] Latitude (WGS84) - * @param lon [degE7] Longitude (WGS84) - * @param alt [m] Altitude (MSL) - * @param vel [m/s] target velocity (0,0,0) for unknown - * @param acc [m/s/s] linear target acceleration (0,0,0) for unknown - * @param attitude_q (0 0 0 0 for unknown) - * @param rates (0 0 0 for unknown) - * @param position_cov eph epv - * @param custom_state button states or switches of a tracker device - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_follow_target_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint64_t timestamp, uint8_t est_capabilities, int32_t lat, int32_t lon, float alt, const float *vel, const float *acc, const float *attitude_q, const float *rates, const float *position_cov, uint64_t custom_state) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_FOLLOW_TARGET_LEN]; - _mav_put_uint64_t(buf, 0, timestamp); - _mav_put_uint64_t(buf, 8, custom_state); - _mav_put_int32_t(buf, 16, lat); - _mav_put_int32_t(buf, 20, lon); - _mav_put_float(buf, 24, alt); - _mav_put_uint8_t(buf, 92, est_capabilities); - _mav_put_float_array(buf, 28, vel, 3); - _mav_put_float_array(buf, 40, acc, 3); - _mav_put_float_array(buf, 52, attitude_q, 4); - _mav_put_float_array(buf, 68, rates, 3); - _mav_put_float_array(buf, 80, position_cov, 3); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FOLLOW_TARGET_LEN); -#else - mavlink_follow_target_t packet; - packet.timestamp = timestamp; - packet.custom_state = custom_state; - packet.lat = lat; - packet.lon = lon; - packet.alt = alt; - packet.est_capabilities = est_capabilities; - mav_array_memcpy(packet.vel, vel, sizeof(float)*3); - mav_array_memcpy(packet.acc, acc, sizeof(float)*3); - mav_array_memcpy(packet.attitude_q, attitude_q, sizeof(float)*4); - mav_array_memcpy(packet.rates, rates, sizeof(float)*3); - mav_array_memcpy(packet.position_cov, position_cov, sizeof(float)*3); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FOLLOW_TARGET_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_FOLLOW_TARGET; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_FOLLOW_TARGET_MIN_LEN, MAVLINK_MSG_ID_FOLLOW_TARGET_LEN, MAVLINK_MSG_ID_FOLLOW_TARGET_CRC); -} - -/** - * @brief Pack a follow_target message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param timestamp [ms] Timestamp (time since system boot). - * @param est_capabilities bit positions for tracker reporting capabilities (POS = 0, VEL = 1, ACCEL = 2, ATT + RATES = 3) - * @param lat [degE7] Latitude (WGS84) - * @param lon [degE7] Longitude (WGS84) - * @param alt [m] Altitude (MSL) - * @param vel [m/s] target velocity (0,0,0) for unknown - * @param acc [m/s/s] linear target acceleration (0,0,0) for unknown - * @param attitude_q (0 0 0 0 for unknown) - * @param rates (0 0 0 for unknown) - * @param position_cov eph epv - * @param custom_state button states or switches of a tracker device - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_follow_target_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint64_t timestamp,uint8_t est_capabilities,int32_t lat,int32_t lon,float alt,const float *vel,const float *acc,const float *attitude_q,const float *rates,const float *position_cov,uint64_t custom_state) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_FOLLOW_TARGET_LEN]; - _mav_put_uint64_t(buf, 0, timestamp); - _mav_put_uint64_t(buf, 8, custom_state); - _mav_put_int32_t(buf, 16, lat); - _mav_put_int32_t(buf, 20, lon); - _mav_put_float(buf, 24, alt); - _mav_put_uint8_t(buf, 92, est_capabilities); - _mav_put_float_array(buf, 28, vel, 3); - _mav_put_float_array(buf, 40, acc, 3); - _mav_put_float_array(buf, 52, attitude_q, 4); - _mav_put_float_array(buf, 68, rates, 3); - _mav_put_float_array(buf, 80, position_cov, 3); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FOLLOW_TARGET_LEN); -#else - mavlink_follow_target_t packet; - packet.timestamp = timestamp; - packet.custom_state = custom_state; - packet.lat = lat; - packet.lon = lon; - packet.alt = alt; - packet.est_capabilities = est_capabilities; - mav_array_memcpy(packet.vel, vel, sizeof(float)*3); - mav_array_memcpy(packet.acc, acc, sizeof(float)*3); - mav_array_memcpy(packet.attitude_q, attitude_q, sizeof(float)*4); - mav_array_memcpy(packet.rates, rates, sizeof(float)*3); - mav_array_memcpy(packet.position_cov, position_cov, sizeof(float)*3); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FOLLOW_TARGET_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_FOLLOW_TARGET; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_FOLLOW_TARGET_MIN_LEN, MAVLINK_MSG_ID_FOLLOW_TARGET_LEN, MAVLINK_MSG_ID_FOLLOW_TARGET_CRC); -} - -/** - * @brief Encode a follow_target struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param follow_target C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_follow_target_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_follow_target_t* follow_target) -{ - return mavlink_msg_follow_target_pack(system_id, component_id, msg, follow_target->timestamp, follow_target->est_capabilities, follow_target->lat, follow_target->lon, follow_target->alt, follow_target->vel, follow_target->acc, follow_target->attitude_q, follow_target->rates, follow_target->position_cov, follow_target->custom_state); -} - -/** - * @brief Encode a follow_target struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param follow_target C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_follow_target_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_follow_target_t* follow_target) -{ - return mavlink_msg_follow_target_pack_chan(system_id, component_id, chan, msg, follow_target->timestamp, follow_target->est_capabilities, follow_target->lat, follow_target->lon, follow_target->alt, follow_target->vel, follow_target->acc, follow_target->attitude_q, follow_target->rates, follow_target->position_cov, follow_target->custom_state); -} - -/** - * @brief Send a follow_target message - * @param chan MAVLink channel to send the message - * - * @param timestamp [ms] Timestamp (time since system boot). - * @param est_capabilities bit positions for tracker reporting capabilities (POS = 0, VEL = 1, ACCEL = 2, ATT + RATES = 3) - * @param lat [degE7] Latitude (WGS84) - * @param lon [degE7] Longitude (WGS84) - * @param alt [m] Altitude (MSL) - * @param vel [m/s] target velocity (0,0,0) for unknown - * @param acc [m/s/s] linear target acceleration (0,0,0) for unknown - * @param attitude_q (0 0 0 0 for unknown) - * @param rates (0 0 0 for unknown) - * @param position_cov eph epv - * @param custom_state button states or switches of a tracker device - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_follow_target_send(mavlink_channel_t chan, uint64_t timestamp, uint8_t est_capabilities, int32_t lat, int32_t lon, float alt, const float *vel, const float *acc, const float *attitude_q, const float *rates, const float *position_cov, uint64_t custom_state) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_FOLLOW_TARGET_LEN]; - _mav_put_uint64_t(buf, 0, timestamp); - _mav_put_uint64_t(buf, 8, custom_state); - _mav_put_int32_t(buf, 16, lat); - _mav_put_int32_t(buf, 20, lon); - _mav_put_float(buf, 24, alt); - _mav_put_uint8_t(buf, 92, est_capabilities); - _mav_put_float_array(buf, 28, vel, 3); - _mav_put_float_array(buf, 40, acc, 3); - _mav_put_float_array(buf, 52, attitude_q, 4); - _mav_put_float_array(buf, 68, rates, 3); - _mav_put_float_array(buf, 80, position_cov, 3); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FOLLOW_TARGET, buf, MAVLINK_MSG_ID_FOLLOW_TARGET_MIN_LEN, MAVLINK_MSG_ID_FOLLOW_TARGET_LEN, MAVLINK_MSG_ID_FOLLOW_TARGET_CRC); -#else - mavlink_follow_target_t packet; - packet.timestamp = timestamp; - packet.custom_state = custom_state; - packet.lat = lat; - packet.lon = lon; - packet.alt = alt; - packet.est_capabilities = est_capabilities; - mav_array_memcpy(packet.vel, vel, sizeof(float)*3); - mav_array_memcpy(packet.acc, acc, sizeof(float)*3); - mav_array_memcpy(packet.attitude_q, attitude_q, sizeof(float)*4); - mav_array_memcpy(packet.rates, rates, sizeof(float)*3); - mav_array_memcpy(packet.position_cov, position_cov, sizeof(float)*3); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FOLLOW_TARGET, (const char *)&packet, MAVLINK_MSG_ID_FOLLOW_TARGET_MIN_LEN, MAVLINK_MSG_ID_FOLLOW_TARGET_LEN, MAVLINK_MSG_ID_FOLLOW_TARGET_CRC); -#endif -} - -/** - * @brief Send a follow_target message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_follow_target_send_struct(mavlink_channel_t chan, const mavlink_follow_target_t* follow_target) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_follow_target_send(chan, follow_target->timestamp, follow_target->est_capabilities, follow_target->lat, follow_target->lon, follow_target->alt, follow_target->vel, follow_target->acc, follow_target->attitude_q, follow_target->rates, follow_target->position_cov, follow_target->custom_state); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FOLLOW_TARGET, (const char *)follow_target, MAVLINK_MSG_ID_FOLLOW_TARGET_MIN_LEN, MAVLINK_MSG_ID_FOLLOW_TARGET_LEN, MAVLINK_MSG_ID_FOLLOW_TARGET_CRC); -#endif -} - -#if MAVLINK_MSG_ID_FOLLOW_TARGET_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_follow_target_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp, uint8_t est_capabilities, int32_t lat, int32_t lon, float alt, const float *vel, const float *acc, const float *attitude_q, const float *rates, const float *position_cov, uint64_t custom_state) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, timestamp); - _mav_put_uint64_t(buf, 8, custom_state); - _mav_put_int32_t(buf, 16, lat); - _mav_put_int32_t(buf, 20, lon); - _mav_put_float(buf, 24, alt); - _mav_put_uint8_t(buf, 92, est_capabilities); - _mav_put_float_array(buf, 28, vel, 3); - _mav_put_float_array(buf, 40, acc, 3); - _mav_put_float_array(buf, 52, attitude_q, 4); - _mav_put_float_array(buf, 68, rates, 3); - _mav_put_float_array(buf, 80, position_cov, 3); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FOLLOW_TARGET, buf, MAVLINK_MSG_ID_FOLLOW_TARGET_MIN_LEN, MAVLINK_MSG_ID_FOLLOW_TARGET_LEN, MAVLINK_MSG_ID_FOLLOW_TARGET_CRC); -#else - mavlink_follow_target_t *packet = (mavlink_follow_target_t *)msgbuf; - packet->timestamp = timestamp; - packet->custom_state = custom_state; - packet->lat = lat; - packet->lon = lon; - packet->alt = alt; - packet->est_capabilities = est_capabilities; - mav_array_memcpy(packet->vel, vel, sizeof(float)*3); - mav_array_memcpy(packet->acc, acc, sizeof(float)*3); - mav_array_memcpy(packet->attitude_q, attitude_q, sizeof(float)*4); - mav_array_memcpy(packet->rates, rates, sizeof(float)*3); - mav_array_memcpy(packet->position_cov, position_cov, sizeof(float)*3); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FOLLOW_TARGET, (const char *)packet, MAVLINK_MSG_ID_FOLLOW_TARGET_MIN_LEN, MAVLINK_MSG_ID_FOLLOW_TARGET_LEN, MAVLINK_MSG_ID_FOLLOW_TARGET_CRC); -#endif -} -#endif - -#endif - -// MESSAGE FOLLOW_TARGET UNPACKING - - -/** - * @brief Get field timestamp from follow_target message - * - * @return [ms] Timestamp (time since system boot). - */ -static inline uint64_t mavlink_msg_follow_target_get_timestamp(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field est_capabilities from follow_target message - * - * @return bit positions for tracker reporting capabilities (POS = 0, VEL = 1, ACCEL = 2, ATT + RATES = 3) - */ -static inline uint8_t mavlink_msg_follow_target_get_est_capabilities(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 92); -} - -/** - * @brief Get field lat from follow_target message - * - * @return [degE7] Latitude (WGS84) - */ -static inline int32_t mavlink_msg_follow_target_get_lat(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 16); -} - -/** - * @brief Get field lon from follow_target message - * - * @return [degE7] Longitude (WGS84) - */ -static inline int32_t mavlink_msg_follow_target_get_lon(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 20); -} - -/** - * @brief Get field alt from follow_target message - * - * @return [m] Altitude (MSL) - */ -static inline float mavlink_msg_follow_target_get_alt(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Get field vel from follow_target message - * - * @return [m/s] target velocity (0,0,0) for unknown - */ -static inline uint16_t mavlink_msg_follow_target_get_vel(const mavlink_message_t* msg, float *vel) -{ - return _MAV_RETURN_float_array(msg, vel, 3, 28); -} - -/** - * @brief Get field acc from follow_target message - * - * @return [m/s/s] linear target acceleration (0,0,0) for unknown - */ -static inline uint16_t mavlink_msg_follow_target_get_acc(const mavlink_message_t* msg, float *acc) -{ - return _MAV_RETURN_float_array(msg, acc, 3, 40); -} - -/** - * @brief Get field attitude_q from follow_target message - * - * @return (0 0 0 0 for unknown) - */ -static inline uint16_t mavlink_msg_follow_target_get_attitude_q(const mavlink_message_t* msg, float *attitude_q) -{ - return _MAV_RETURN_float_array(msg, attitude_q, 4, 52); -} - -/** - * @brief Get field rates from follow_target message - * - * @return (0 0 0 for unknown) - */ -static inline uint16_t mavlink_msg_follow_target_get_rates(const mavlink_message_t* msg, float *rates) -{ - return _MAV_RETURN_float_array(msg, rates, 3, 68); -} - -/** - * @brief Get field position_cov from follow_target message - * - * @return eph epv - */ -static inline uint16_t mavlink_msg_follow_target_get_position_cov(const mavlink_message_t* msg, float *position_cov) -{ - return _MAV_RETURN_float_array(msg, position_cov, 3, 80); -} - -/** - * @brief Get field custom_state from follow_target message - * - * @return button states or switches of a tracker device - */ -static inline uint64_t mavlink_msg_follow_target_get_custom_state(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 8); -} - -/** - * @brief Decode a follow_target message into a struct - * - * @param msg The message to decode - * @param follow_target C-struct to decode the message contents into - */ -static inline void mavlink_msg_follow_target_decode(const mavlink_message_t* msg, mavlink_follow_target_t* follow_target) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - follow_target->timestamp = mavlink_msg_follow_target_get_timestamp(msg); - follow_target->custom_state = mavlink_msg_follow_target_get_custom_state(msg); - follow_target->lat = mavlink_msg_follow_target_get_lat(msg); - follow_target->lon = mavlink_msg_follow_target_get_lon(msg); - follow_target->alt = mavlink_msg_follow_target_get_alt(msg); - mavlink_msg_follow_target_get_vel(msg, follow_target->vel); - mavlink_msg_follow_target_get_acc(msg, follow_target->acc); - mavlink_msg_follow_target_get_attitude_q(msg, follow_target->attitude_q); - mavlink_msg_follow_target_get_rates(msg, follow_target->rates); - mavlink_msg_follow_target_get_position_cov(msg, follow_target->position_cov); - follow_target->est_capabilities = mavlink_msg_follow_target_get_est_capabilities(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_FOLLOW_TARGET_LEN? msg->len : MAVLINK_MSG_ID_FOLLOW_TARGET_LEN; - memset(follow_target, 0, MAVLINK_MSG_ID_FOLLOW_TARGET_LEN); - memcpy(follow_target, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_generator_status.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_generator_status.h deleted file mode 100644 index a8e1a448..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_generator_status.h +++ /dev/null @@ -1,463 +0,0 @@ -#pragma once -// MESSAGE GENERATOR_STATUS PACKING - -#define MAVLINK_MSG_ID_GENERATOR_STATUS 373 - - -typedef struct __mavlink_generator_status_t { - uint64_t status; /*< Status flags.*/ - float battery_current; /*< [A] Current into/out of battery. Positive for out. Negative for in. NaN: field not provided.*/ - float load_current; /*< [A] Current going to the UAV. If battery current not available this is the DC current from the generator. Positive for out. Negative for in. NaN: field not provided*/ - float power_generated; /*< [W] The power being generated. NaN: field not provided*/ - float bus_voltage; /*< [V] Voltage of the bus seen at the generator, or battery bus if battery bus is controlled by generator and at a different voltage to main bus.*/ - float bat_current_setpoint; /*< [A] The target battery current. Positive for out. Negative for in. NaN: field not provided*/ - uint32_t runtime; /*< [s] Seconds this generator has run since it was rebooted. UINT32_MAX: field not provided.*/ - int32_t time_until_maintenance; /*< [s] Seconds until this generator requires maintenance. A negative value indicates maintenance is past-due. INT32_MAX: field not provided.*/ - uint16_t generator_speed; /*< [rpm] Speed of electrical generator or alternator. UINT16_MAX: field not provided.*/ - int16_t rectifier_temperature; /*< [degC] The temperature of the rectifier or power converter. INT16_MAX: field not provided.*/ - int16_t generator_temperature; /*< [degC] The temperature of the mechanical motor, fuel cell core or generator. INT16_MAX: field not provided.*/ -} mavlink_generator_status_t; - -#define MAVLINK_MSG_ID_GENERATOR_STATUS_LEN 42 -#define MAVLINK_MSG_ID_GENERATOR_STATUS_MIN_LEN 42 -#define MAVLINK_MSG_ID_373_LEN 42 -#define MAVLINK_MSG_ID_373_MIN_LEN 42 - -#define MAVLINK_MSG_ID_GENERATOR_STATUS_CRC 117 -#define MAVLINK_MSG_ID_373_CRC 117 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_GENERATOR_STATUS { \ - 373, \ - "GENERATOR_STATUS", \ - 11, \ - { { "status", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_generator_status_t, status) }, \ - { "generator_speed", NULL, MAVLINK_TYPE_UINT16_T, 0, 36, offsetof(mavlink_generator_status_t, generator_speed) }, \ - { "battery_current", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_generator_status_t, battery_current) }, \ - { "load_current", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_generator_status_t, load_current) }, \ - { "power_generated", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_generator_status_t, power_generated) }, \ - { "bus_voltage", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_generator_status_t, bus_voltage) }, \ - { "rectifier_temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 38, offsetof(mavlink_generator_status_t, rectifier_temperature) }, \ - { "bat_current_setpoint", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_generator_status_t, bat_current_setpoint) }, \ - { "generator_temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 40, offsetof(mavlink_generator_status_t, generator_temperature) }, \ - { "runtime", NULL, MAVLINK_TYPE_UINT32_T, 0, 28, offsetof(mavlink_generator_status_t, runtime) }, \ - { "time_until_maintenance", NULL, MAVLINK_TYPE_INT32_T, 0, 32, offsetof(mavlink_generator_status_t, time_until_maintenance) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_GENERATOR_STATUS { \ - "GENERATOR_STATUS", \ - 11, \ - { { "status", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_generator_status_t, status) }, \ - { "generator_speed", NULL, MAVLINK_TYPE_UINT16_T, 0, 36, offsetof(mavlink_generator_status_t, generator_speed) }, \ - { "battery_current", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_generator_status_t, battery_current) }, \ - { "load_current", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_generator_status_t, load_current) }, \ - { "power_generated", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_generator_status_t, power_generated) }, \ - { "bus_voltage", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_generator_status_t, bus_voltage) }, \ - { "rectifier_temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 38, offsetof(mavlink_generator_status_t, rectifier_temperature) }, \ - { "bat_current_setpoint", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_generator_status_t, bat_current_setpoint) }, \ - { "generator_temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 40, offsetof(mavlink_generator_status_t, generator_temperature) }, \ - { "runtime", NULL, MAVLINK_TYPE_UINT32_T, 0, 28, offsetof(mavlink_generator_status_t, runtime) }, \ - { "time_until_maintenance", NULL, MAVLINK_TYPE_INT32_T, 0, 32, offsetof(mavlink_generator_status_t, time_until_maintenance) }, \ - } \ -} -#endif - -/** - * @brief Pack a generator_status message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param status Status flags. - * @param generator_speed [rpm] Speed of electrical generator or alternator. UINT16_MAX: field not provided. - * @param battery_current [A] Current into/out of battery. Positive for out. Negative for in. NaN: field not provided. - * @param load_current [A] Current going to the UAV. If battery current not available this is the DC current from the generator. Positive for out. Negative for in. NaN: field not provided - * @param power_generated [W] The power being generated. NaN: field not provided - * @param bus_voltage [V] Voltage of the bus seen at the generator, or battery bus if battery bus is controlled by generator and at a different voltage to main bus. - * @param rectifier_temperature [degC] The temperature of the rectifier or power converter. INT16_MAX: field not provided. - * @param bat_current_setpoint [A] The target battery current. Positive for out. Negative for in. NaN: field not provided - * @param generator_temperature [degC] The temperature of the mechanical motor, fuel cell core or generator. INT16_MAX: field not provided. - * @param runtime [s] Seconds this generator has run since it was rebooted. UINT32_MAX: field not provided. - * @param time_until_maintenance [s] Seconds until this generator requires maintenance. A negative value indicates maintenance is past-due. INT32_MAX: field not provided. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_generator_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint64_t status, uint16_t generator_speed, float battery_current, float load_current, float power_generated, float bus_voltage, int16_t rectifier_temperature, float bat_current_setpoint, int16_t generator_temperature, uint32_t runtime, int32_t time_until_maintenance) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_GENERATOR_STATUS_LEN]; - _mav_put_uint64_t(buf, 0, status); - _mav_put_float(buf, 8, battery_current); - _mav_put_float(buf, 12, load_current); - _mav_put_float(buf, 16, power_generated); - _mav_put_float(buf, 20, bus_voltage); - _mav_put_float(buf, 24, bat_current_setpoint); - _mav_put_uint32_t(buf, 28, runtime); - _mav_put_int32_t(buf, 32, time_until_maintenance); - _mav_put_uint16_t(buf, 36, generator_speed); - _mav_put_int16_t(buf, 38, rectifier_temperature); - _mav_put_int16_t(buf, 40, generator_temperature); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GENERATOR_STATUS_LEN); -#else - mavlink_generator_status_t packet; - packet.status = status; - packet.battery_current = battery_current; - packet.load_current = load_current; - packet.power_generated = power_generated; - packet.bus_voltage = bus_voltage; - packet.bat_current_setpoint = bat_current_setpoint; - packet.runtime = runtime; - packet.time_until_maintenance = time_until_maintenance; - packet.generator_speed = generator_speed; - packet.rectifier_temperature = rectifier_temperature; - packet.generator_temperature = generator_temperature; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GENERATOR_STATUS_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_GENERATOR_STATUS; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GENERATOR_STATUS_MIN_LEN, MAVLINK_MSG_ID_GENERATOR_STATUS_LEN, MAVLINK_MSG_ID_GENERATOR_STATUS_CRC); -} - -/** - * @brief Pack a generator_status message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param status Status flags. - * @param generator_speed [rpm] Speed of electrical generator or alternator. UINT16_MAX: field not provided. - * @param battery_current [A] Current into/out of battery. Positive for out. Negative for in. NaN: field not provided. - * @param load_current [A] Current going to the UAV. If battery current not available this is the DC current from the generator. Positive for out. Negative for in. NaN: field not provided - * @param power_generated [W] The power being generated. NaN: field not provided - * @param bus_voltage [V] Voltage of the bus seen at the generator, or battery bus if battery bus is controlled by generator and at a different voltage to main bus. - * @param rectifier_temperature [degC] The temperature of the rectifier or power converter. INT16_MAX: field not provided. - * @param bat_current_setpoint [A] The target battery current. Positive for out. Negative for in. NaN: field not provided - * @param generator_temperature [degC] The temperature of the mechanical motor, fuel cell core or generator. INT16_MAX: field not provided. - * @param runtime [s] Seconds this generator has run since it was rebooted. UINT32_MAX: field not provided. - * @param time_until_maintenance [s] Seconds until this generator requires maintenance. A negative value indicates maintenance is past-due. INT32_MAX: field not provided. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_generator_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint64_t status,uint16_t generator_speed,float battery_current,float load_current,float power_generated,float bus_voltage,int16_t rectifier_temperature,float bat_current_setpoint,int16_t generator_temperature,uint32_t runtime,int32_t time_until_maintenance) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_GENERATOR_STATUS_LEN]; - _mav_put_uint64_t(buf, 0, status); - _mav_put_float(buf, 8, battery_current); - _mav_put_float(buf, 12, load_current); - _mav_put_float(buf, 16, power_generated); - _mav_put_float(buf, 20, bus_voltage); - _mav_put_float(buf, 24, bat_current_setpoint); - _mav_put_uint32_t(buf, 28, runtime); - _mav_put_int32_t(buf, 32, time_until_maintenance); - _mav_put_uint16_t(buf, 36, generator_speed); - _mav_put_int16_t(buf, 38, rectifier_temperature); - _mav_put_int16_t(buf, 40, generator_temperature); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GENERATOR_STATUS_LEN); -#else - mavlink_generator_status_t packet; - packet.status = status; - packet.battery_current = battery_current; - packet.load_current = load_current; - packet.power_generated = power_generated; - packet.bus_voltage = bus_voltage; - packet.bat_current_setpoint = bat_current_setpoint; - packet.runtime = runtime; - packet.time_until_maintenance = time_until_maintenance; - packet.generator_speed = generator_speed; - packet.rectifier_temperature = rectifier_temperature; - packet.generator_temperature = generator_temperature; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GENERATOR_STATUS_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_GENERATOR_STATUS; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GENERATOR_STATUS_MIN_LEN, MAVLINK_MSG_ID_GENERATOR_STATUS_LEN, MAVLINK_MSG_ID_GENERATOR_STATUS_CRC); -} - -/** - * @brief Encode a generator_status struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param generator_status C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_generator_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_generator_status_t* generator_status) -{ - return mavlink_msg_generator_status_pack(system_id, component_id, msg, generator_status->status, generator_status->generator_speed, generator_status->battery_current, generator_status->load_current, generator_status->power_generated, generator_status->bus_voltage, generator_status->rectifier_temperature, generator_status->bat_current_setpoint, generator_status->generator_temperature, generator_status->runtime, generator_status->time_until_maintenance); -} - -/** - * @brief Encode a generator_status struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param generator_status C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_generator_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_generator_status_t* generator_status) -{ - return mavlink_msg_generator_status_pack_chan(system_id, component_id, chan, msg, generator_status->status, generator_status->generator_speed, generator_status->battery_current, generator_status->load_current, generator_status->power_generated, generator_status->bus_voltage, generator_status->rectifier_temperature, generator_status->bat_current_setpoint, generator_status->generator_temperature, generator_status->runtime, generator_status->time_until_maintenance); -} - -/** - * @brief Send a generator_status message - * @param chan MAVLink channel to send the message - * - * @param status Status flags. - * @param generator_speed [rpm] Speed of electrical generator or alternator. UINT16_MAX: field not provided. - * @param battery_current [A] Current into/out of battery. Positive for out. Negative for in. NaN: field not provided. - * @param load_current [A] Current going to the UAV. If battery current not available this is the DC current from the generator. Positive for out. Negative for in. NaN: field not provided - * @param power_generated [W] The power being generated. NaN: field not provided - * @param bus_voltage [V] Voltage of the bus seen at the generator, or battery bus if battery bus is controlled by generator and at a different voltage to main bus. - * @param rectifier_temperature [degC] The temperature of the rectifier or power converter. INT16_MAX: field not provided. - * @param bat_current_setpoint [A] The target battery current. Positive for out. Negative for in. NaN: field not provided - * @param generator_temperature [degC] The temperature of the mechanical motor, fuel cell core or generator. INT16_MAX: field not provided. - * @param runtime [s] Seconds this generator has run since it was rebooted. UINT32_MAX: field not provided. - * @param time_until_maintenance [s] Seconds until this generator requires maintenance. A negative value indicates maintenance is past-due. INT32_MAX: field not provided. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_generator_status_send(mavlink_channel_t chan, uint64_t status, uint16_t generator_speed, float battery_current, float load_current, float power_generated, float bus_voltage, int16_t rectifier_temperature, float bat_current_setpoint, int16_t generator_temperature, uint32_t runtime, int32_t time_until_maintenance) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_GENERATOR_STATUS_LEN]; - _mav_put_uint64_t(buf, 0, status); - _mav_put_float(buf, 8, battery_current); - _mav_put_float(buf, 12, load_current); - _mav_put_float(buf, 16, power_generated); - _mav_put_float(buf, 20, bus_voltage); - _mav_put_float(buf, 24, bat_current_setpoint); - _mav_put_uint32_t(buf, 28, runtime); - _mav_put_int32_t(buf, 32, time_until_maintenance); - _mav_put_uint16_t(buf, 36, generator_speed); - _mav_put_int16_t(buf, 38, rectifier_temperature); - _mav_put_int16_t(buf, 40, generator_temperature); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GENERATOR_STATUS, buf, MAVLINK_MSG_ID_GENERATOR_STATUS_MIN_LEN, MAVLINK_MSG_ID_GENERATOR_STATUS_LEN, MAVLINK_MSG_ID_GENERATOR_STATUS_CRC); -#else - mavlink_generator_status_t packet; - packet.status = status; - packet.battery_current = battery_current; - packet.load_current = load_current; - packet.power_generated = power_generated; - packet.bus_voltage = bus_voltage; - packet.bat_current_setpoint = bat_current_setpoint; - packet.runtime = runtime; - packet.time_until_maintenance = time_until_maintenance; - packet.generator_speed = generator_speed; - packet.rectifier_temperature = rectifier_temperature; - packet.generator_temperature = generator_temperature; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GENERATOR_STATUS, (const char *)&packet, MAVLINK_MSG_ID_GENERATOR_STATUS_MIN_LEN, MAVLINK_MSG_ID_GENERATOR_STATUS_LEN, MAVLINK_MSG_ID_GENERATOR_STATUS_CRC); -#endif -} - -/** - * @brief Send a generator_status message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_generator_status_send_struct(mavlink_channel_t chan, const mavlink_generator_status_t* generator_status) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_generator_status_send(chan, generator_status->status, generator_status->generator_speed, generator_status->battery_current, generator_status->load_current, generator_status->power_generated, generator_status->bus_voltage, generator_status->rectifier_temperature, generator_status->bat_current_setpoint, generator_status->generator_temperature, generator_status->runtime, generator_status->time_until_maintenance); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GENERATOR_STATUS, (const char *)generator_status, MAVLINK_MSG_ID_GENERATOR_STATUS_MIN_LEN, MAVLINK_MSG_ID_GENERATOR_STATUS_LEN, MAVLINK_MSG_ID_GENERATOR_STATUS_CRC); -#endif -} - -#if MAVLINK_MSG_ID_GENERATOR_STATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_generator_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t status, uint16_t generator_speed, float battery_current, float load_current, float power_generated, float bus_voltage, int16_t rectifier_temperature, float bat_current_setpoint, int16_t generator_temperature, uint32_t runtime, int32_t time_until_maintenance) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, status); - _mav_put_float(buf, 8, battery_current); - _mav_put_float(buf, 12, load_current); - _mav_put_float(buf, 16, power_generated); - _mav_put_float(buf, 20, bus_voltage); - _mav_put_float(buf, 24, bat_current_setpoint); - _mav_put_uint32_t(buf, 28, runtime); - _mav_put_int32_t(buf, 32, time_until_maintenance); - _mav_put_uint16_t(buf, 36, generator_speed); - _mav_put_int16_t(buf, 38, rectifier_temperature); - _mav_put_int16_t(buf, 40, generator_temperature); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GENERATOR_STATUS, buf, MAVLINK_MSG_ID_GENERATOR_STATUS_MIN_LEN, MAVLINK_MSG_ID_GENERATOR_STATUS_LEN, MAVLINK_MSG_ID_GENERATOR_STATUS_CRC); -#else - mavlink_generator_status_t *packet = (mavlink_generator_status_t *)msgbuf; - packet->status = status; - packet->battery_current = battery_current; - packet->load_current = load_current; - packet->power_generated = power_generated; - packet->bus_voltage = bus_voltage; - packet->bat_current_setpoint = bat_current_setpoint; - packet->runtime = runtime; - packet->time_until_maintenance = time_until_maintenance; - packet->generator_speed = generator_speed; - packet->rectifier_temperature = rectifier_temperature; - packet->generator_temperature = generator_temperature; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GENERATOR_STATUS, (const char *)packet, MAVLINK_MSG_ID_GENERATOR_STATUS_MIN_LEN, MAVLINK_MSG_ID_GENERATOR_STATUS_LEN, MAVLINK_MSG_ID_GENERATOR_STATUS_CRC); -#endif -} -#endif - -#endif - -// MESSAGE GENERATOR_STATUS UNPACKING - - -/** - * @brief Get field status from generator_status message - * - * @return Status flags. - */ -static inline uint64_t mavlink_msg_generator_status_get_status(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field generator_speed from generator_status message - * - * @return [rpm] Speed of electrical generator or alternator. UINT16_MAX: field not provided. - */ -static inline uint16_t mavlink_msg_generator_status_get_generator_speed(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 36); -} - -/** - * @brief Get field battery_current from generator_status message - * - * @return [A] Current into/out of battery. Positive for out. Negative for in. NaN: field not provided. - */ -static inline float mavlink_msg_generator_status_get_battery_current(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field load_current from generator_status message - * - * @return [A] Current going to the UAV. If battery current not available this is the DC current from the generator. Positive for out. Negative for in. NaN: field not provided - */ -static inline float mavlink_msg_generator_status_get_load_current(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field power_generated from generator_status message - * - * @return [W] The power being generated. NaN: field not provided - */ -static inline float mavlink_msg_generator_status_get_power_generated(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field bus_voltage from generator_status message - * - * @return [V] Voltage of the bus seen at the generator, or battery bus if battery bus is controlled by generator and at a different voltage to main bus. - */ -static inline float mavlink_msg_generator_status_get_bus_voltage(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Get field rectifier_temperature from generator_status message - * - * @return [degC] The temperature of the rectifier or power converter. INT16_MAX: field not provided. - */ -static inline int16_t mavlink_msg_generator_status_get_rectifier_temperature(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 38); -} - -/** - * @brief Get field bat_current_setpoint from generator_status message - * - * @return [A] The target battery current. Positive for out. Negative for in. NaN: field not provided - */ -static inline float mavlink_msg_generator_status_get_bat_current_setpoint(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Get field generator_temperature from generator_status message - * - * @return [degC] The temperature of the mechanical motor, fuel cell core or generator. INT16_MAX: field not provided. - */ -static inline int16_t mavlink_msg_generator_status_get_generator_temperature(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 40); -} - -/** - * @brief Get field runtime from generator_status message - * - * @return [s] Seconds this generator has run since it was rebooted. UINT32_MAX: field not provided. - */ -static inline uint32_t mavlink_msg_generator_status_get_runtime(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 28); -} - -/** - * @brief Get field time_until_maintenance from generator_status message - * - * @return [s] Seconds until this generator requires maintenance. A negative value indicates maintenance is past-due. INT32_MAX: field not provided. - */ -static inline int32_t mavlink_msg_generator_status_get_time_until_maintenance(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 32); -} - -/** - * @brief Decode a generator_status message into a struct - * - * @param msg The message to decode - * @param generator_status C-struct to decode the message contents into - */ -static inline void mavlink_msg_generator_status_decode(const mavlink_message_t* msg, mavlink_generator_status_t* generator_status) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - generator_status->status = mavlink_msg_generator_status_get_status(msg); - generator_status->battery_current = mavlink_msg_generator_status_get_battery_current(msg); - generator_status->load_current = mavlink_msg_generator_status_get_load_current(msg); - generator_status->power_generated = mavlink_msg_generator_status_get_power_generated(msg); - generator_status->bus_voltage = mavlink_msg_generator_status_get_bus_voltage(msg); - generator_status->bat_current_setpoint = mavlink_msg_generator_status_get_bat_current_setpoint(msg); - generator_status->runtime = mavlink_msg_generator_status_get_runtime(msg); - generator_status->time_until_maintenance = mavlink_msg_generator_status_get_time_until_maintenance(msg); - generator_status->generator_speed = mavlink_msg_generator_status_get_generator_speed(msg); - generator_status->rectifier_temperature = mavlink_msg_generator_status_get_rectifier_temperature(msg); - generator_status->generator_temperature = mavlink_msg_generator_status_get_generator_temperature(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_GENERATOR_STATUS_LEN? msg->len : MAVLINK_MSG_ID_GENERATOR_STATUS_LEN; - memset(generator_status, 0, MAVLINK_MSG_ID_GENERATOR_STATUS_LEN); - memcpy(generator_status, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_gimbal_device_attitude_status.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_gimbal_device_attitude_status.h deleted file mode 100644 index 12ed1eb9..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_gimbal_device_attitude_status.h +++ /dev/null @@ -1,480 +0,0 @@ -#pragma once -// MESSAGE GIMBAL_DEVICE_ATTITUDE_STATUS PACKING - -#define MAVLINK_MSG_ID_GIMBAL_DEVICE_ATTITUDE_STATUS 285 - - -typedef struct __mavlink_gimbal_device_attitude_status_t { - uint32_t time_boot_ms; /*< [ms] Timestamp (time since system boot).*/ - float q[4]; /*< Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation). The frame is described in the message description.*/ - float angular_velocity_x; /*< [rad/s] X component of angular velocity (positive: rolling to the right). The frame is described in the message description. NaN if unknown.*/ - float angular_velocity_y; /*< [rad/s] Y component of angular velocity (positive: pitching up). The frame is described in the message description. NaN if unknown.*/ - float angular_velocity_z; /*< [rad/s] Z component of angular velocity (positive: yawing to the right). The frame is described in the message description. NaN if unknown.*/ - uint32_t failure_flags; /*< Failure flags (0 for no failure)*/ - uint16_t flags; /*< Current gimbal flags set.*/ - uint8_t target_system; /*< System ID*/ - uint8_t target_component; /*< Component ID*/ - float delta_yaw; /*< [rad] Yaw angle relating the quaternions in earth and body frames (see message description). NaN if unknown.*/ - float delta_yaw_velocity; /*< [rad/s] Yaw angular velocity relating the angular velocities in earth and body frames (see message description). NaN if unknown.*/ - uint8_t gimbal_device_id; /*< This field is to be used if the gimbal manager and the gimbal device are the same component and hence have the same component ID. This field is then set a number between 1-6. If the component ID is separate, this field is not required and must be set to 0.*/ -} mavlink_gimbal_device_attitude_status_t; - -#define MAVLINK_MSG_ID_GIMBAL_DEVICE_ATTITUDE_STATUS_LEN 49 -#define MAVLINK_MSG_ID_GIMBAL_DEVICE_ATTITUDE_STATUS_MIN_LEN 40 -#define MAVLINK_MSG_ID_285_LEN 49 -#define MAVLINK_MSG_ID_285_MIN_LEN 40 - -#define MAVLINK_MSG_ID_GIMBAL_DEVICE_ATTITUDE_STATUS_CRC 137 -#define MAVLINK_MSG_ID_285_CRC 137 - -#define MAVLINK_MSG_GIMBAL_DEVICE_ATTITUDE_STATUS_FIELD_Q_LEN 4 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_GIMBAL_DEVICE_ATTITUDE_STATUS { \ - 285, \ - "GIMBAL_DEVICE_ATTITUDE_STATUS", \ - 12, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 38, offsetof(mavlink_gimbal_device_attitude_status_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 39, offsetof(mavlink_gimbal_device_attitude_status_t, target_component) }, \ - { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_gimbal_device_attitude_status_t, time_boot_ms) }, \ - { "flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 36, offsetof(mavlink_gimbal_device_attitude_status_t, flags) }, \ - { "q", NULL, MAVLINK_TYPE_FLOAT, 4, 4, offsetof(mavlink_gimbal_device_attitude_status_t, q) }, \ - { "angular_velocity_x", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_gimbal_device_attitude_status_t, angular_velocity_x) }, \ - { "angular_velocity_y", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_gimbal_device_attitude_status_t, angular_velocity_y) }, \ - { "angular_velocity_z", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_gimbal_device_attitude_status_t, angular_velocity_z) }, \ - { "failure_flags", NULL, MAVLINK_TYPE_UINT32_T, 0, 32, offsetof(mavlink_gimbal_device_attitude_status_t, failure_flags) }, \ - { "delta_yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_gimbal_device_attitude_status_t, delta_yaw) }, \ - { "delta_yaw_velocity", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_gimbal_device_attitude_status_t, delta_yaw_velocity) }, \ - { "gimbal_device_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 48, offsetof(mavlink_gimbal_device_attitude_status_t, gimbal_device_id) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_GIMBAL_DEVICE_ATTITUDE_STATUS { \ - "GIMBAL_DEVICE_ATTITUDE_STATUS", \ - 12, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 38, offsetof(mavlink_gimbal_device_attitude_status_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 39, offsetof(mavlink_gimbal_device_attitude_status_t, target_component) }, \ - { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_gimbal_device_attitude_status_t, time_boot_ms) }, \ - { "flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 36, offsetof(mavlink_gimbal_device_attitude_status_t, flags) }, \ - { "q", NULL, MAVLINK_TYPE_FLOAT, 4, 4, offsetof(mavlink_gimbal_device_attitude_status_t, q) }, \ - { "angular_velocity_x", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_gimbal_device_attitude_status_t, angular_velocity_x) }, \ - { "angular_velocity_y", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_gimbal_device_attitude_status_t, angular_velocity_y) }, \ - { "angular_velocity_z", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_gimbal_device_attitude_status_t, angular_velocity_z) }, \ - { "failure_flags", NULL, MAVLINK_TYPE_UINT32_T, 0, 32, offsetof(mavlink_gimbal_device_attitude_status_t, failure_flags) }, \ - { "delta_yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_gimbal_device_attitude_status_t, delta_yaw) }, \ - { "delta_yaw_velocity", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_gimbal_device_attitude_status_t, delta_yaw_velocity) }, \ - { "gimbal_device_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 48, offsetof(mavlink_gimbal_device_attitude_status_t, gimbal_device_id) }, \ - } \ -} -#endif - -/** - * @brief Pack a gimbal_device_attitude_status message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID - * @param target_component Component ID - * @param time_boot_ms [ms] Timestamp (time since system boot). - * @param flags Current gimbal flags set. - * @param q Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation). The frame is described in the message description. - * @param angular_velocity_x [rad/s] X component of angular velocity (positive: rolling to the right). The frame is described in the message description. NaN if unknown. - * @param angular_velocity_y [rad/s] Y component of angular velocity (positive: pitching up). The frame is described in the message description. NaN if unknown. - * @param angular_velocity_z [rad/s] Z component of angular velocity (positive: yawing to the right). The frame is described in the message description. NaN if unknown. - * @param failure_flags Failure flags (0 for no failure) - * @param delta_yaw [rad] Yaw angle relating the quaternions in earth and body frames (see message description). NaN if unknown. - * @param delta_yaw_velocity [rad/s] Yaw angular velocity relating the angular velocities in earth and body frames (see message description). NaN if unknown. - * @param gimbal_device_id This field is to be used if the gimbal manager and the gimbal device are the same component and hence have the same component ID. This field is then set a number between 1-6. If the component ID is separate, this field is not required and must be set to 0. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_gimbal_device_attitude_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component, uint32_t time_boot_ms, uint16_t flags, const float *q, float angular_velocity_x, float angular_velocity_y, float angular_velocity_z, uint32_t failure_flags, float delta_yaw, float delta_yaw_velocity, uint8_t gimbal_device_id) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_GIMBAL_DEVICE_ATTITUDE_STATUS_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 20, angular_velocity_x); - _mav_put_float(buf, 24, angular_velocity_y); - _mav_put_float(buf, 28, angular_velocity_z); - _mav_put_uint32_t(buf, 32, failure_flags); - _mav_put_uint16_t(buf, 36, flags); - _mav_put_uint8_t(buf, 38, target_system); - _mav_put_uint8_t(buf, 39, target_component); - _mav_put_float(buf, 40, delta_yaw); - _mav_put_float(buf, 44, delta_yaw_velocity); - _mav_put_uint8_t(buf, 48, gimbal_device_id); - _mav_put_float_array(buf, 4, q, 4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GIMBAL_DEVICE_ATTITUDE_STATUS_LEN); -#else - mavlink_gimbal_device_attitude_status_t packet; - packet.time_boot_ms = time_boot_ms; - packet.angular_velocity_x = angular_velocity_x; - packet.angular_velocity_y = angular_velocity_y; - packet.angular_velocity_z = angular_velocity_z; - packet.failure_flags = failure_flags; - packet.flags = flags; - packet.target_system = target_system; - packet.target_component = target_component; - packet.delta_yaw = delta_yaw; - packet.delta_yaw_velocity = delta_yaw_velocity; - packet.gimbal_device_id = gimbal_device_id; - mav_array_memcpy(packet.q, q, sizeof(float)*4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GIMBAL_DEVICE_ATTITUDE_STATUS_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_GIMBAL_DEVICE_ATTITUDE_STATUS; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GIMBAL_DEVICE_ATTITUDE_STATUS_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_DEVICE_ATTITUDE_STATUS_LEN, MAVLINK_MSG_ID_GIMBAL_DEVICE_ATTITUDE_STATUS_CRC); -} - -/** - * @brief Pack a gimbal_device_attitude_status message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @param time_boot_ms [ms] Timestamp (time since system boot). - * @param flags Current gimbal flags set. - * @param q Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation). The frame is described in the message description. - * @param angular_velocity_x [rad/s] X component of angular velocity (positive: rolling to the right). The frame is described in the message description. NaN if unknown. - * @param angular_velocity_y [rad/s] Y component of angular velocity (positive: pitching up). The frame is described in the message description. NaN if unknown. - * @param angular_velocity_z [rad/s] Z component of angular velocity (positive: yawing to the right). The frame is described in the message description. NaN if unknown. - * @param failure_flags Failure flags (0 for no failure) - * @param delta_yaw [rad] Yaw angle relating the quaternions in earth and body frames (see message description). NaN if unknown. - * @param delta_yaw_velocity [rad/s] Yaw angular velocity relating the angular velocities in earth and body frames (see message description). NaN if unknown. - * @param gimbal_device_id This field is to be used if the gimbal manager and the gimbal device are the same component and hence have the same component ID. This field is then set a number between 1-6. If the component ID is separate, this field is not required and must be set to 0. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_gimbal_device_attitude_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component,uint32_t time_boot_ms,uint16_t flags,const float *q,float angular_velocity_x,float angular_velocity_y,float angular_velocity_z,uint32_t failure_flags,float delta_yaw,float delta_yaw_velocity,uint8_t gimbal_device_id) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_GIMBAL_DEVICE_ATTITUDE_STATUS_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 20, angular_velocity_x); - _mav_put_float(buf, 24, angular_velocity_y); - _mav_put_float(buf, 28, angular_velocity_z); - _mav_put_uint32_t(buf, 32, failure_flags); - _mav_put_uint16_t(buf, 36, flags); - _mav_put_uint8_t(buf, 38, target_system); - _mav_put_uint8_t(buf, 39, target_component); - _mav_put_float(buf, 40, delta_yaw); - _mav_put_float(buf, 44, delta_yaw_velocity); - _mav_put_uint8_t(buf, 48, gimbal_device_id); - _mav_put_float_array(buf, 4, q, 4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GIMBAL_DEVICE_ATTITUDE_STATUS_LEN); -#else - mavlink_gimbal_device_attitude_status_t packet; - packet.time_boot_ms = time_boot_ms; - packet.angular_velocity_x = angular_velocity_x; - packet.angular_velocity_y = angular_velocity_y; - packet.angular_velocity_z = angular_velocity_z; - packet.failure_flags = failure_flags; - packet.flags = flags; - packet.target_system = target_system; - packet.target_component = target_component; - packet.delta_yaw = delta_yaw; - packet.delta_yaw_velocity = delta_yaw_velocity; - packet.gimbal_device_id = gimbal_device_id; - mav_array_memcpy(packet.q, q, sizeof(float)*4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GIMBAL_DEVICE_ATTITUDE_STATUS_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_GIMBAL_DEVICE_ATTITUDE_STATUS; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GIMBAL_DEVICE_ATTITUDE_STATUS_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_DEVICE_ATTITUDE_STATUS_LEN, MAVLINK_MSG_ID_GIMBAL_DEVICE_ATTITUDE_STATUS_CRC); -} - -/** - * @brief Encode a gimbal_device_attitude_status struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param gimbal_device_attitude_status C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_gimbal_device_attitude_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gimbal_device_attitude_status_t* gimbal_device_attitude_status) -{ - return mavlink_msg_gimbal_device_attitude_status_pack(system_id, component_id, msg, gimbal_device_attitude_status->target_system, gimbal_device_attitude_status->target_component, gimbal_device_attitude_status->time_boot_ms, gimbal_device_attitude_status->flags, gimbal_device_attitude_status->q, gimbal_device_attitude_status->angular_velocity_x, gimbal_device_attitude_status->angular_velocity_y, gimbal_device_attitude_status->angular_velocity_z, gimbal_device_attitude_status->failure_flags, gimbal_device_attitude_status->delta_yaw, gimbal_device_attitude_status->delta_yaw_velocity, gimbal_device_attitude_status->gimbal_device_id); -} - -/** - * @brief Encode a gimbal_device_attitude_status struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param gimbal_device_attitude_status C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_gimbal_device_attitude_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_gimbal_device_attitude_status_t* gimbal_device_attitude_status) -{ - return mavlink_msg_gimbal_device_attitude_status_pack_chan(system_id, component_id, chan, msg, gimbal_device_attitude_status->target_system, gimbal_device_attitude_status->target_component, gimbal_device_attitude_status->time_boot_ms, gimbal_device_attitude_status->flags, gimbal_device_attitude_status->q, gimbal_device_attitude_status->angular_velocity_x, gimbal_device_attitude_status->angular_velocity_y, gimbal_device_attitude_status->angular_velocity_z, gimbal_device_attitude_status->failure_flags, gimbal_device_attitude_status->delta_yaw, gimbal_device_attitude_status->delta_yaw_velocity, gimbal_device_attitude_status->gimbal_device_id); -} - -/** - * @brief Send a gimbal_device_attitude_status message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param target_component Component ID - * @param time_boot_ms [ms] Timestamp (time since system boot). - * @param flags Current gimbal flags set. - * @param q Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation). The frame is described in the message description. - * @param angular_velocity_x [rad/s] X component of angular velocity (positive: rolling to the right). The frame is described in the message description. NaN if unknown. - * @param angular_velocity_y [rad/s] Y component of angular velocity (positive: pitching up). The frame is described in the message description. NaN if unknown. - * @param angular_velocity_z [rad/s] Z component of angular velocity (positive: yawing to the right). The frame is described in the message description. NaN if unknown. - * @param failure_flags Failure flags (0 for no failure) - * @param delta_yaw [rad] Yaw angle relating the quaternions in earth and body frames (see message description). NaN if unknown. - * @param delta_yaw_velocity [rad/s] Yaw angular velocity relating the angular velocities in earth and body frames (see message description). NaN if unknown. - * @param gimbal_device_id This field is to be used if the gimbal manager and the gimbal device are the same component and hence have the same component ID. This field is then set a number between 1-6. If the component ID is separate, this field is not required and must be set to 0. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_gimbal_device_attitude_status_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint32_t time_boot_ms, uint16_t flags, const float *q, float angular_velocity_x, float angular_velocity_y, float angular_velocity_z, uint32_t failure_flags, float delta_yaw, float delta_yaw_velocity, uint8_t gimbal_device_id) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_GIMBAL_DEVICE_ATTITUDE_STATUS_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 20, angular_velocity_x); - _mav_put_float(buf, 24, angular_velocity_y); - _mav_put_float(buf, 28, angular_velocity_z); - _mav_put_uint32_t(buf, 32, failure_flags); - _mav_put_uint16_t(buf, 36, flags); - _mav_put_uint8_t(buf, 38, target_system); - _mav_put_uint8_t(buf, 39, target_component); - _mav_put_float(buf, 40, delta_yaw); - _mav_put_float(buf, 44, delta_yaw_velocity); - _mav_put_uint8_t(buf, 48, gimbal_device_id); - _mav_put_float_array(buf, 4, q, 4); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_DEVICE_ATTITUDE_STATUS, buf, MAVLINK_MSG_ID_GIMBAL_DEVICE_ATTITUDE_STATUS_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_DEVICE_ATTITUDE_STATUS_LEN, MAVLINK_MSG_ID_GIMBAL_DEVICE_ATTITUDE_STATUS_CRC); -#else - mavlink_gimbal_device_attitude_status_t packet; - packet.time_boot_ms = time_boot_ms; - packet.angular_velocity_x = angular_velocity_x; - packet.angular_velocity_y = angular_velocity_y; - packet.angular_velocity_z = angular_velocity_z; - packet.failure_flags = failure_flags; - packet.flags = flags; - packet.target_system = target_system; - packet.target_component = target_component; - packet.delta_yaw = delta_yaw; - packet.delta_yaw_velocity = delta_yaw_velocity; - packet.gimbal_device_id = gimbal_device_id; - mav_array_memcpy(packet.q, q, sizeof(float)*4); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_DEVICE_ATTITUDE_STATUS, (const char *)&packet, MAVLINK_MSG_ID_GIMBAL_DEVICE_ATTITUDE_STATUS_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_DEVICE_ATTITUDE_STATUS_LEN, MAVLINK_MSG_ID_GIMBAL_DEVICE_ATTITUDE_STATUS_CRC); -#endif -} - -/** - * @brief Send a gimbal_device_attitude_status message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_gimbal_device_attitude_status_send_struct(mavlink_channel_t chan, const mavlink_gimbal_device_attitude_status_t* gimbal_device_attitude_status) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_gimbal_device_attitude_status_send(chan, gimbal_device_attitude_status->target_system, gimbal_device_attitude_status->target_component, gimbal_device_attitude_status->time_boot_ms, gimbal_device_attitude_status->flags, gimbal_device_attitude_status->q, gimbal_device_attitude_status->angular_velocity_x, gimbal_device_attitude_status->angular_velocity_y, gimbal_device_attitude_status->angular_velocity_z, gimbal_device_attitude_status->failure_flags, gimbal_device_attitude_status->delta_yaw, gimbal_device_attitude_status->delta_yaw_velocity, gimbal_device_attitude_status->gimbal_device_id); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_DEVICE_ATTITUDE_STATUS, (const char *)gimbal_device_attitude_status, MAVLINK_MSG_ID_GIMBAL_DEVICE_ATTITUDE_STATUS_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_DEVICE_ATTITUDE_STATUS_LEN, MAVLINK_MSG_ID_GIMBAL_DEVICE_ATTITUDE_STATUS_CRC); -#endif -} - -#if MAVLINK_MSG_ID_GIMBAL_DEVICE_ATTITUDE_STATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_gimbal_device_attitude_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint32_t time_boot_ms, uint16_t flags, const float *q, float angular_velocity_x, float angular_velocity_y, float angular_velocity_z, uint32_t failure_flags, float delta_yaw, float delta_yaw_velocity, uint8_t gimbal_device_id) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 20, angular_velocity_x); - _mav_put_float(buf, 24, angular_velocity_y); - _mav_put_float(buf, 28, angular_velocity_z); - _mav_put_uint32_t(buf, 32, failure_flags); - _mav_put_uint16_t(buf, 36, flags); - _mav_put_uint8_t(buf, 38, target_system); - _mav_put_uint8_t(buf, 39, target_component); - _mav_put_float(buf, 40, delta_yaw); - _mav_put_float(buf, 44, delta_yaw_velocity); - _mav_put_uint8_t(buf, 48, gimbal_device_id); - _mav_put_float_array(buf, 4, q, 4); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_DEVICE_ATTITUDE_STATUS, buf, MAVLINK_MSG_ID_GIMBAL_DEVICE_ATTITUDE_STATUS_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_DEVICE_ATTITUDE_STATUS_LEN, MAVLINK_MSG_ID_GIMBAL_DEVICE_ATTITUDE_STATUS_CRC); -#else - mavlink_gimbal_device_attitude_status_t *packet = (mavlink_gimbal_device_attitude_status_t *)msgbuf; - packet->time_boot_ms = time_boot_ms; - packet->angular_velocity_x = angular_velocity_x; - packet->angular_velocity_y = angular_velocity_y; - packet->angular_velocity_z = angular_velocity_z; - packet->failure_flags = failure_flags; - packet->flags = flags; - packet->target_system = target_system; - packet->target_component = target_component; - packet->delta_yaw = delta_yaw; - packet->delta_yaw_velocity = delta_yaw_velocity; - packet->gimbal_device_id = gimbal_device_id; - mav_array_memcpy(packet->q, q, sizeof(float)*4); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_DEVICE_ATTITUDE_STATUS, (const char *)packet, MAVLINK_MSG_ID_GIMBAL_DEVICE_ATTITUDE_STATUS_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_DEVICE_ATTITUDE_STATUS_LEN, MAVLINK_MSG_ID_GIMBAL_DEVICE_ATTITUDE_STATUS_CRC); -#endif -} -#endif - -#endif - -// MESSAGE GIMBAL_DEVICE_ATTITUDE_STATUS UNPACKING - - -/** - * @brief Get field target_system from gimbal_device_attitude_status message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_gimbal_device_attitude_status_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 38); -} - -/** - * @brief Get field target_component from gimbal_device_attitude_status message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_gimbal_device_attitude_status_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 39); -} - -/** - * @brief Get field time_boot_ms from gimbal_device_attitude_status message - * - * @return [ms] Timestamp (time since system boot). - */ -static inline uint32_t mavlink_msg_gimbal_device_attitude_status_get_time_boot_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field flags from gimbal_device_attitude_status message - * - * @return Current gimbal flags set. - */ -static inline uint16_t mavlink_msg_gimbal_device_attitude_status_get_flags(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 36); -} - -/** - * @brief Get field q from gimbal_device_attitude_status message - * - * @return Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation). The frame is described in the message description. - */ -static inline uint16_t mavlink_msg_gimbal_device_attitude_status_get_q(const mavlink_message_t* msg, float *q) -{ - return _MAV_RETURN_float_array(msg, q, 4, 4); -} - -/** - * @brief Get field angular_velocity_x from gimbal_device_attitude_status message - * - * @return [rad/s] X component of angular velocity (positive: rolling to the right). The frame is described in the message description. NaN if unknown. - */ -static inline float mavlink_msg_gimbal_device_attitude_status_get_angular_velocity_x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Get field angular_velocity_y from gimbal_device_attitude_status message - * - * @return [rad/s] Y component of angular velocity (positive: pitching up). The frame is described in the message description. NaN if unknown. - */ -static inline float mavlink_msg_gimbal_device_attitude_status_get_angular_velocity_y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Get field angular_velocity_z from gimbal_device_attitude_status message - * - * @return [rad/s] Z component of angular velocity (positive: yawing to the right). The frame is described in the message description. NaN if unknown. - */ -static inline float mavlink_msg_gimbal_device_attitude_status_get_angular_velocity_z(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 28); -} - -/** - * @brief Get field failure_flags from gimbal_device_attitude_status message - * - * @return Failure flags (0 for no failure) - */ -static inline uint32_t mavlink_msg_gimbal_device_attitude_status_get_failure_flags(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 32); -} - -/** - * @brief Get field delta_yaw from gimbal_device_attitude_status message - * - * @return [rad] Yaw angle relating the quaternions in earth and body frames (see message description). NaN if unknown. - */ -static inline float mavlink_msg_gimbal_device_attitude_status_get_delta_yaw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 40); -} - -/** - * @brief Get field delta_yaw_velocity from gimbal_device_attitude_status message - * - * @return [rad/s] Yaw angular velocity relating the angular velocities in earth and body frames (see message description). NaN if unknown. - */ -static inline float mavlink_msg_gimbal_device_attitude_status_get_delta_yaw_velocity(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 44); -} - -/** - * @brief Get field gimbal_device_id from gimbal_device_attitude_status message - * - * @return This field is to be used if the gimbal manager and the gimbal device are the same component and hence have the same component ID. This field is then set a number between 1-6. If the component ID is separate, this field is not required and must be set to 0. - */ -static inline uint8_t mavlink_msg_gimbal_device_attitude_status_get_gimbal_device_id(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 48); -} - -/** - * @brief Decode a gimbal_device_attitude_status message into a struct - * - * @param msg The message to decode - * @param gimbal_device_attitude_status C-struct to decode the message contents into - */ -static inline void mavlink_msg_gimbal_device_attitude_status_decode(const mavlink_message_t* msg, mavlink_gimbal_device_attitude_status_t* gimbal_device_attitude_status) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - gimbal_device_attitude_status->time_boot_ms = mavlink_msg_gimbal_device_attitude_status_get_time_boot_ms(msg); - mavlink_msg_gimbal_device_attitude_status_get_q(msg, gimbal_device_attitude_status->q); - gimbal_device_attitude_status->angular_velocity_x = mavlink_msg_gimbal_device_attitude_status_get_angular_velocity_x(msg); - gimbal_device_attitude_status->angular_velocity_y = mavlink_msg_gimbal_device_attitude_status_get_angular_velocity_y(msg); - gimbal_device_attitude_status->angular_velocity_z = mavlink_msg_gimbal_device_attitude_status_get_angular_velocity_z(msg); - gimbal_device_attitude_status->failure_flags = mavlink_msg_gimbal_device_attitude_status_get_failure_flags(msg); - gimbal_device_attitude_status->flags = mavlink_msg_gimbal_device_attitude_status_get_flags(msg); - gimbal_device_attitude_status->target_system = mavlink_msg_gimbal_device_attitude_status_get_target_system(msg); - gimbal_device_attitude_status->target_component = mavlink_msg_gimbal_device_attitude_status_get_target_component(msg); - gimbal_device_attitude_status->delta_yaw = mavlink_msg_gimbal_device_attitude_status_get_delta_yaw(msg); - gimbal_device_attitude_status->delta_yaw_velocity = mavlink_msg_gimbal_device_attitude_status_get_delta_yaw_velocity(msg); - gimbal_device_attitude_status->gimbal_device_id = mavlink_msg_gimbal_device_attitude_status_get_gimbal_device_id(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_GIMBAL_DEVICE_ATTITUDE_STATUS_LEN? msg->len : MAVLINK_MSG_ID_GIMBAL_DEVICE_ATTITUDE_STATUS_LEN; - memset(gimbal_device_attitude_status, 0, MAVLINK_MSG_ID_GIMBAL_DEVICE_ATTITUDE_STATUS_LEN); - memcpy(gimbal_device_attitude_status, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_gimbal_device_information.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_gimbal_device_information.h deleted file mode 100644 index 4969bfa6..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_gimbal_device_information.h +++ /dev/null @@ -1,582 +0,0 @@ -#pragma once -// MESSAGE GIMBAL_DEVICE_INFORMATION PACKING - -#define MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION 283 - - -typedef struct __mavlink_gimbal_device_information_t { - uint64_t uid; /*< UID of gimbal hardware (0 if unknown).*/ - uint32_t time_boot_ms; /*< [ms] Timestamp (time since system boot).*/ - uint32_t firmware_version; /*< Version of the gimbal firmware, encoded as: (Dev & 0xff) << 24 | (Patch & 0xff) << 16 | (Minor & 0xff) << 8 | (Major & 0xff).*/ - uint32_t hardware_version; /*< Version of the gimbal hardware, encoded as: (Dev & 0xff) << 24 | (Patch & 0xff) << 16 | (Minor & 0xff) << 8 | (Major & 0xff).*/ - float roll_min; /*< [rad] Minimum hardware roll angle (positive: rolling to the right, negative: rolling to the left). NAN if unknown.*/ - float roll_max; /*< [rad] Maximum hardware roll angle (positive: rolling to the right, negative: rolling to the left). NAN if unknown.*/ - float pitch_min; /*< [rad] Minimum hardware pitch angle (positive: up, negative: down). NAN if unknown.*/ - float pitch_max; /*< [rad] Maximum hardware pitch angle (positive: up, negative: down). NAN if unknown.*/ - float yaw_min; /*< [rad] Minimum hardware yaw angle (positive: to the right, negative: to the left). NAN if unknown.*/ - float yaw_max; /*< [rad] Maximum hardware yaw angle (positive: to the right, negative: to the left). NAN if unknown.*/ - uint16_t cap_flags; /*< Bitmap of gimbal capability flags.*/ - uint16_t custom_cap_flags; /*< Bitmap for use for gimbal-specific capability flags.*/ - char vendor_name[32]; /*< Name of the gimbal vendor.*/ - char model_name[32]; /*< Name of the gimbal model.*/ - char custom_name[32]; /*< Custom name of the gimbal given to it by the user.*/ - uint8_t gimbal_device_id; /*< This field is to be used if the gimbal manager and the gimbal device are the same component and hence have the same component ID. This field is then set to a number between 1-6. If the component ID is separate, this field is not required and must be set to 0.*/ -} mavlink_gimbal_device_information_t; - -#define MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION_LEN 145 -#define MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION_MIN_LEN 144 -#define MAVLINK_MSG_ID_283_LEN 145 -#define MAVLINK_MSG_ID_283_MIN_LEN 144 - -#define MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION_CRC 74 -#define MAVLINK_MSG_ID_283_CRC 74 - -#define MAVLINK_MSG_GIMBAL_DEVICE_INFORMATION_FIELD_VENDOR_NAME_LEN 32 -#define MAVLINK_MSG_GIMBAL_DEVICE_INFORMATION_FIELD_MODEL_NAME_LEN 32 -#define MAVLINK_MSG_GIMBAL_DEVICE_INFORMATION_FIELD_CUSTOM_NAME_LEN 32 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_GIMBAL_DEVICE_INFORMATION { \ - 283, \ - "GIMBAL_DEVICE_INFORMATION", \ - 16, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_gimbal_device_information_t, time_boot_ms) }, \ - { "vendor_name", NULL, MAVLINK_TYPE_CHAR, 32, 48, offsetof(mavlink_gimbal_device_information_t, vendor_name) }, \ - { "model_name", NULL, MAVLINK_TYPE_CHAR, 32, 80, offsetof(mavlink_gimbal_device_information_t, model_name) }, \ - { "custom_name", NULL, MAVLINK_TYPE_CHAR, 32, 112, offsetof(mavlink_gimbal_device_information_t, custom_name) }, \ - { "firmware_version", NULL, MAVLINK_TYPE_UINT32_T, 0, 12, offsetof(mavlink_gimbal_device_information_t, firmware_version) }, \ - { "hardware_version", NULL, MAVLINK_TYPE_UINT32_T, 0, 16, offsetof(mavlink_gimbal_device_information_t, hardware_version) }, \ - { "uid", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_gimbal_device_information_t, uid) }, \ - { "cap_flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 44, offsetof(mavlink_gimbal_device_information_t, cap_flags) }, \ - { "custom_cap_flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 46, offsetof(mavlink_gimbal_device_information_t, custom_cap_flags) }, \ - { "roll_min", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_gimbal_device_information_t, roll_min) }, \ - { "roll_max", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_gimbal_device_information_t, roll_max) }, \ - { "pitch_min", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_gimbal_device_information_t, pitch_min) }, \ - { "pitch_max", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_gimbal_device_information_t, pitch_max) }, \ - { "yaw_min", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_gimbal_device_information_t, yaw_min) }, \ - { "yaw_max", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_gimbal_device_information_t, yaw_max) }, \ - { "gimbal_device_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 144, offsetof(mavlink_gimbal_device_information_t, gimbal_device_id) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_GIMBAL_DEVICE_INFORMATION { \ - "GIMBAL_DEVICE_INFORMATION", \ - 16, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_gimbal_device_information_t, time_boot_ms) }, \ - { "vendor_name", NULL, MAVLINK_TYPE_CHAR, 32, 48, offsetof(mavlink_gimbal_device_information_t, vendor_name) }, \ - { "model_name", NULL, MAVLINK_TYPE_CHAR, 32, 80, offsetof(mavlink_gimbal_device_information_t, model_name) }, \ - { "custom_name", NULL, MAVLINK_TYPE_CHAR, 32, 112, offsetof(mavlink_gimbal_device_information_t, custom_name) }, \ - { "firmware_version", NULL, MAVLINK_TYPE_UINT32_T, 0, 12, offsetof(mavlink_gimbal_device_information_t, firmware_version) }, \ - { "hardware_version", NULL, MAVLINK_TYPE_UINT32_T, 0, 16, offsetof(mavlink_gimbal_device_information_t, hardware_version) }, \ - { "uid", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_gimbal_device_information_t, uid) }, \ - { "cap_flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 44, offsetof(mavlink_gimbal_device_information_t, cap_flags) }, \ - { "custom_cap_flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 46, offsetof(mavlink_gimbal_device_information_t, custom_cap_flags) }, \ - { "roll_min", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_gimbal_device_information_t, roll_min) }, \ - { "roll_max", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_gimbal_device_information_t, roll_max) }, \ - { "pitch_min", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_gimbal_device_information_t, pitch_min) }, \ - { "pitch_max", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_gimbal_device_information_t, pitch_max) }, \ - { "yaw_min", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_gimbal_device_information_t, yaw_min) }, \ - { "yaw_max", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_gimbal_device_information_t, yaw_max) }, \ - { "gimbal_device_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 144, offsetof(mavlink_gimbal_device_information_t, gimbal_device_id) }, \ - } \ -} -#endif - -/** - * @brief Pack a gimbal_device_information message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param time_boot_ms [ms] Timestamp (time since system boot). - * @param vendor_name Name of the gimbal vendor. - * @param model_name Name of the gimbal model. - * @param custom_name Custom name of the gimbal given to it by the user. - * @param firmware_version Version of the gimbal firmware, encoded as: (Dev & 0xff) << 24 | (Patch & 0xff) << 16 | (Minor & 0xff) << 8 | (Major & 0xff). - * @param hardware_version Version of the gimbal hardware, encoded as: (Dev & 0xff) << 24 | (Patch & 0xff) << 16 | (Minor & 0xff) << 8 | (Major & 0xff). - * @param uid UID of gimbal hardware (0 if unknown). - * @param cap_flags Bitmap of gimbal capability flags. - * @param custom_cap_flags Bitmap for use for gimbal-specific capability flags. - * @param roll_min [rad] Minimum hardware roll angle (positive: rolling to the right, negative: rolling to the left). NAN if unknown. - * @param roll_max [rad] Maximum hardware roll angle (positive: rolling to the right, negative: rolling to the left). NAN if unknown. - * @param pitch_min [rad] Minimum hardware pitch angle (positive: up, negative: down). NAN if unknown. - * @param pitch_max [rad] Maximum hardware pitch angle (positive: up, negative: down). NAN if unknown. - * @param yaw_min [rad] Minimum hardware yaw angle (positive: to the right, negative: to the left). NAN if unknown. - * @param yaw_max [rad] Maximum hardware yaw angle (positive: to the right, negative: to the left). NAN if unknown. - * @param gimbal_device_id This field is to be used if the gimbal manager and the gimbal device are the same component and hence have the same component ID. This field is then set to a number between 1-6. If the component ID is separate, this field is not required and must be set to 0. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_gimbal_device_information_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint32_t time_boot_ms, const char *vendor_name, const char *model_name, const char *custom_name, uint32_t firmware_version, uint32_t hardware_version, uint64_t uid, uint16_t cap_flags, uint16_t custom_cap_flags, float roll_min, float roll_max, float pitch_min, float pitch_max, float yaw_min, float yaw_max, uint8_t gimbal_device_id) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION_LEN]; - _mav_put_uint64_t(buf, 0, uid); - _mav_put_uint32_t(buf, 8, time_boot_ms); - _mav_put_uint32_t(buf, 12, firmware_version); - _mav_put_uint32_t(buf, 16, hardware_version); - _mav_put_float(buf, 20, roll_min); - _mav_put_float(buf, 24, roll_max); - _mav_put_float(buf, 28, pitch_min); - _mav_put_float(buf, 32, pitch_max); - _mav_put_float(buf, 36, yaw_min); - _mav_put_float(buf, 40, yaw_max); - _mav_put_uint16_t(buf, 44, cap_flags); - _mav_put_uint16_t(buf, 46, custom_cap_flags); - _mav_put_uint8_t(buf, 144, gimbal_device_id); - _mav_put_char_array(buf, 48, vendor_name, 32); - _mav_put_char_array(buf, 80, model_name, 32); - _mav_put_char_array(buf, 112, custom_name, 32); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION_LEN); -#else - mavlink_gimbal_device_information_t packet; - packet.uid = uid; - packet.time_boot_ms = time_boot_ms; - packet.firmware_version = firmware_version; - packet.hardware_version = hardware_version; - packet.roll_min = roll_min; - packet.roll_max = roll_max; - packet.pitch_min = pitch_min; - packet.pitch_max = pitch_max; - packet.yaw_min = yaw_min; - packet.yaw_max = yaw_max; - packet.cap_flags = cap_flags; - packet.custom_cap_flags = custom_cap_flags; - packet.gimbal_device_id = gimbal_device_id; - mav_array_memcpy(packet.vendor_name, vendor_name, sizeof(char)*32); - mav_array_memcpy(packet.model_name, model_name, sizeof(char)*32); - mav_array_memcpy(packet.custom_name, custom_name, sizeof(char)*32); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION_LEN, MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION_CRC); -} - -/** - * @brief Pack a gimbal_device_information message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_boot_ms [ms] Timestamp (time since system boot). - * @param vendor_name Name of the gimbal vendor. - * @param model_name Name of the gimbal model. - * @param custom_name Custom name of the gimbal given to it by the user. - * @param firmware_version Version of the gimbal firmware, encoded as: (Dev & 0xff) << 24 | (Patch & 0xff) << 16 | (Minor & 0xff) << 8 | (Major & 0xff). - * @param hardware_version Version of the gimbal hardware, encoded as: (Dev & 0xff) << 24 | (Patch & 0xff) << 16 | (Minor & 0xff) << 8 | (Major & 0xff). - * @param uid UID of gimbal hardware (0 if unknown). - * @param cap_flags Bitmap of gimbal capability flags. - * @param custom_cap_flags Bitmap for use for gimbal-specific capability flags. - * @param roll_min [rad] Minimum hardware roll angle (positive: rolling to the right, negative: rolling to the left). NAN if unknown. - * @param roll_max [rad] Maximum hardware roll angle (positive: rolling to the right, negative: rolling to the left). NAN if unknown. - * @param pitch_min [rad] Minimum hardware pitch angle (positive: up, negative: down). NAN if unknown. - * @param pitch_max [rad] Maximum hardware pitch angle (positive: up, negative: down). NAN if unknown. - * @param yaw_min [rad] Minimum hardware yaw angle (positive: to the right, negative: to the left). NAN if unknown. - * @param yaw_max [rad] Maximum hardware yaw angle (positive: to the right, negative: to the left). NAN if unknown. - * @param gimbal_device_id This field is to be used if the gimbal manager and the gimbal device are the same component and hence have the same component ID. This field is then set to a number between 1-6. If the component ID is separate, this field is not required and must be set to 0. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_gimbal_device_information_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint32_t time_boot_ms,const char *vendor_name,const char *model_name,const char *custom_name,uint32_t firmware_version,uint32_t hardware_version,uint64_t uid,uint16_t cap_flags,uint16_t custom_cap_flags,float roll_min,float roll_max,float pitch_min,float pitch_max,float yaw_min,float yaw_max,uint8_t gimbal_device_id) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION_LEN]; - _mav_put_uint64_t(buf, 0, uid); - _mav_put_uint32_t(buf, 8, time_boot_ms); - _mav_put_uint32_t(buf, 12, firmware_version); - _mav_put_uint32_t(buf, 16, hardware_version); - _mav_put_float(buf, 20, roll_min); - _mav_put_float(buf, 24, roll_max); - _mav_put_float(buf, 28, pitch_min); - _mav_put_float(buf, 32, pitch_max); - _mav_put_float(buf, 36, yaw_min); - _mav_put_float(buf, 40, yaw_max); - _mav_put_uint16_t(buf, 44, cap_flags); - _mav_put_uint16_t(buf, 46, custom_cap_flags); - _mav_put_uint8_t(buf, 144, gimbal_device_id); - _mav_put_char_array(buf, 48, vendor_name, 32); - _mav_put_char_array(buf, 80, model_name, 32); - _mav_put_char_array(buf, 112, custom_name, 32); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION_LEN); -#else - mavlink_gimbal_device_information_t packet; - packet.uid = uid; - packet.time_boot_ms = time_boot_ms; - packet.firmware_version = firmware_version; - packet.hardware_version = hardware_version; - packet.roll_min = roll_min; - packet.roll_max = roll_max; - packet.pitch_min = pitch_min; - packet.pitch_max = pitch_max; - packet.yaw_min = yaw_min; - packet.yaw_max = yaw_max; - packet.cap_flags = cap_flags; - packet.custom_cap_flags = custom_cap_flags; - packet.gimbal_device_id = gimbal_device_id; - mav_array_memcpy(packet.vendor_name, vendor_name, sizeof(char)*32); - mav_array_memcpy(packet.model_name, model_name, sizeof(char)*32); - mav_array_memcpy(packet.custom_name, custom_name, sizeof(char)*32); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION_LEN, MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION_CRC); -} - -/** - * @brief Encode a gimbal_device_information struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param gimbal_device_information C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_gimbal_device_information_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gimbal_device_information_t* gimbal_device_information) -{ - return mavlink_msg_gimbal_device_information_pack(system_id, component_id, msg, gimbal_device_information->time_boot_ms, gimbal_device_information->vendor_name, gimbal_device_information->model_name, gimbal_device_information->custom_name, gimbal_device_information->firmware_version, gimbal_device_information->hardware_version, gimbal_device_information->uid, gimbal_device_information->cap_flags, gimbal_device_information->custom_cap_flags, gimbal_device_information->roll_min, gimbal_device_information->roll_max, gimbal_device_information->pitch_min, gimbal_device_information->pitch_max, gimbal_device_information->yaw_min, gimbal_device_information->yaw_max, gimbal_device_information->gimbal_device_id); -} - -/** - * @brief Encode a gimbal_device_information struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param gimbal_device_information C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_gimbal_device_information_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_gimbal_device_information_t* gimbal_device_information) -{ - return mavlink_msg_gimbal_device_information_pack_chan(system_id, component_id, chan, msg, gimbal_device_information->time_boot_ms, gimbal_device_information->vendor_name, gimbal_device_information->model_name, gimbal_device_information->custom_name, gimbal_device_information->firmware_version, gimbal_device_information->hardware_version, gimbal_device_information->uid, gimbal_device_information->cap_flags, gimbal_device_information->custom_cap_flags, gimbal_device_information->roll_min, gimbal_device_information->roll_max, gimbal_device_information->pitch_min, gimbal_device_information->pitch_max, gimbal_device_information->yaw_min, gimbal_device_information->yaw_max, gimbal_device_information->gimbal_device_id); -} - -/** - * @brief Send a gimbal_device_information message - * @param chan MAVLink channel to send the message - * - * @param time_boot_ms [ms] Timestamp (time since system boot). - * @param vendor_name Name of the gimbal vendor. - * @param model_name Name of the gimbal model. - * @param custom_name Custom name of the gimbal given to it by the user. - * @param firmware_version Version of the gimbal firmware, encoded as: (Dev & 0xff) << 24 | (Patch & 0xff) << 16 | (Minor & 0xff) << 8 | (Major & 0xff). - * @param hardware_version Version of the gimbal hardware, encoded as: (Dev & 0xff) << 24 | (Patch & 0xff) << 16 | (Minor & 0xff) << 8 | (Major & 0xff). - * @param uid UID of gimbal hardware (0 if unknown). - * @param cap_flags Bitmap of gimbal capability flags. - * @param custom_cap_flags Bitmap for use for gimbal-specific capability flags. - * @param roll_min [rad] Minimum hardware roll angle (positive: rolling to the right, negative: rolling to the left). NAN if unknown. - * @param roll_max [rad] Maximum hardware roll angle (positive: rolling to the right, negative: rolling to the left). NAN if unknown. - * @param pitch_min [rad] Minimum hardware pitch angle (positive: up, negative: down). NAN if unknown. - * @param pitch_max [rad] Maximum hardware pitch angle (positive: up, negative: down). NAN if unknown. - * @param yaw_min [rad] Minimum hardware yaw angle (positive: to the right, negative: to the left). NAN if unknown. - * @param yaw_max [rad] Maximum hardware yaw angle (positive: to the right, negative: to the left). NAN if unknown. - * @param gimbal_device_id This field is to be used if the gimbal manager and the gimbal device are the same component and hence have the same component ID. This field is then set to a number between 1-6. If the component ID is separate, this field is not required and must be set to 0. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_gimbal_device_information_send(mavlink_channel_t chan, uint32_t time_boot_ms, const char *vendor_name, const char *model_name, const char *custom_name, uint32_t firmware_version, uint32_t hardware_version, uint64_t uid, uint16_t cap_flags, uint16_t custom_cap_flags, float roll_min, float roll_max, float pitch_min, float pitch_max, float yaw_min, float yaw_max, uint8_t gimbal_device_id) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION_LEN]; - _mav_put_uint64_t(buf, 0, uid); - _mav_put_uint32_t(buf, 8, time_boot_ms); - _mav_put_uint32_t(buf, 12, firmware_version); - _mav_put_uint32_t(buf, 16, hardware_version); - _mav_put_float(buf, 20, roll_min); - _mav_put_float(buf, 24, roll_max); - _mav_put_float(buf, 28, pitch_min); - _mav_put_float(buf, 32, pitch_max); - _mav_put_float(buf, 36, yaw_min); - _mav_put_float(buf, 40, yaw_max); - _mav_put_uint16_t(buf, 44, cap_flags); - _mav_put_uint16_t(buf, 46, custom_cap_flags); - _mav_put_uint8_t(buf, 144, gimbal_device_id); - _mav_put_char_array(buf, 48, vendor_name, 32); - _mav_put_char_array(buf, 80, model_name, 32); - _mav_put_char_array(buf, 112, custom_name, 32); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION, buf, MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION_LEN, MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION_CRC); -#else - mavlink_gimbal_device_information_t packet; - packet.uid = uid; - packet.time_boot_ms = time_boot_ms; - packet.firmware_version = firmware_version; - packet.hardware_version = hardware_version; - packet.roll_min = roll_min; - packet.roll_max = roll_max; - packet.pitch_min = pitch_min; - packet.pitch_max = pitch_max; - packet.yaw_min = yaw_min; - packet.yaw_max = yaw_max; - packet.cap_flags = cap_flags; - packet.custom_cap_flags = custom_cap_flags; - packet.gimbal_device_id = gimbal_device_id; - mav_array_memcpy(packet.vendor_name, vendor_name, sizeof(char)*32); - mav_array_memcpy(packet.model_name, model_name, sizeof(char)*32); - mav_array_memcpy(packet.custom_name, custom_name, sizeof(char)*32); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION, (const char *)&packet, MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION_LEN, MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION_CRC); -#endif -} - -/** - * @brief Send a gimbal_device_information message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_gimbal_device_information_send_struct(mavlink_channel_t chan, const mavlink_gimbal_device_information_t* gimbal_device_information) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_gimbal_device_information_send(chan, gimbal_device_information->time_boot_ms, gimbal_device_information->vendor_name, gimbal_device_information->model_name, gimbal_device_information->custom_name, gimbal_device_information->firmware_version, gimbal_device_information->hardware_version, gimbal_device_information->uid, gimbal_device_information->cap_flags, gimbal_device_information->custom_cap_flags, gimbal_device_information->roll_min, gimbal_device_information->roll_max, gimbal_device_information->pitch_min, gimbal_device_information->pitch_max, gimbal_device_information->yaw_min, gimbal_device_information->yaw_max, gimbal_device_information->gimbal_device_id); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION, (const char *)gimbal_device_information, MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION_LEN, MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION_CRC); -#endif -} - -#if MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_gimbal_device_information_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, const char *vendor_name, const char *model_name, const char *custom_name, uint32_t firmware_version, uint32_t hardware_version, uint64_t uid, uint16_t cap_flags, uint16_t custom_cap_flags, float roll_min, float roll_max, float pitch_min, float pitch_max, float yaw_min, float yaw_max, uint8_t gimbal_device_id) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, uid); - _mav_put_uint32_t(buf, 8, time_boot_ms); - _mav_put_uint32_t(buf, 12, firmware_version); - _mav_put_uint32_t(buf, 16, hardware_version); - _mav_put_float(buf, 20, roll_min); - _mav_put_float(buf, 24, roll_max); - _mav_put_float(buf, 28, pitch_min); - _mav_put_float(buf, 32, pitch_max); - _mav_put_float(buf, 36, yaw_min); - _mav_put_float(buf, 40, yaw_max); - _mav_put_uint16_t(buf, 44, cap_flags); - _mav_put_uint16_t(buf, 46, custom_cap_flags); - _mav_put_uint8_t(buf, 144, gimbal_device_id); - _mav_put_char_array(buf, 48, vendor_name, 32); - _mav_put_char_array(buf, 80, model_name, 32); - _mav_put_char_array(buf, 112, custom_name, 32); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION, buf, MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION_LEN, MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION_CRC); -#else - mavlink_gimbal_device_information_t *packet = (mavlink_gimbal_device_information_t *)msgbuf; - packet->uid = uid; - packet->time_boot_ms = time_boot_ms; - packet->firmware_version = firmware_version; - packet->hardware_version = hardware_version; - packet->roll_min = roll_min; - packet->roll_max = roll_max; - packet->pitch_min = pitch_min; - packet->pitch_max = pitch_max; - packet->yaw_min = yaw_min; - packet->yaw_max = yaw_max; - packet->cap_flags = cap_flags; - packet->custom_cap_flags = custom_cap_flags; - packet->gimbal_device_id = gimbal_device_id; - mav_array_memcpy(packet->vendor_name, vendor_name, sizeof(char)*32); - mav_array_memcpy(packet->model_name, model_name, sizeof(char)*32); - mav_array_memcpy(packet->custom_name, custom_name, sizeof(char)*32); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION, (const char *)packet, MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION_LEN, MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION_CRC); -#endif -} -#endif - -#endif - -// MESSAGE GIMBAL_DEVICE_INFORMATION UNPACKING - - -/** - * @brief Get field time_boot_ms from gimbal_device_information message - * - * @return [ms] Timestamp (time since system boot). - */ -static inline uint32_t mavlink_msg_gimbal_device_information_get_time_boot_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 8); -} - -/** - * @brief Get field vendor_name from gimbal_device_information message - * - * @return Name of the gimbal vendor. - */ -static inline uint16_t mavlink_msg_gimbal_device_information_get_vendor_name(const mavlink_message_t* msg, char *vendor_name) -{ - return _MAV_RETURN_char_array(msg, vendor_name, 32, 48); -} - -/** - * @brief Get field model_name from gimbal_device_information message - * - * @return Name of the gimbal model. - */ -static inline uint16_t mavlink_msg_gimbal_device_information_get_model_name(const mavlink_message_t* msg, char *model_name) -{ - return _MAV_RETURN_char_array(msg, model_name, 32, 80); -} - -/** - * @brief Get field custom_name from gimbal_device_information message - * - * @return Custom name of the gimbal given to it by the user. - */ -static inline uint16_t mavlink_msg_gimbal_device_information_get_custom_name(const mavlink_message_t* msg, char *custom_name) -{ - return _MAV_RETURN_char_array(msg, custom_name, 32, 112); -} - -/** - * @brief Get field firmware_version from gimbal_device_information message - * - * @return Version of the gimbal firmware, encoded as: (Dev & 0xff) << 24 | (Patch & 0xff) << 16 | (Minor & 0xff) << 8 | (Major & 0xff). - */ -static inline uint32_t mavlink_msg_gimbal_device_information_get_firmware_version(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 12); -} - -/** - * @brief Get field hardware_version from gimbal_device_information message - * - * @return Version of the gimbal hardware, encoded as: (Dev & 0xff) << 24 | (Patch & 0xff) << 16 | (Minor & 0xff) << 8 | (Major & 0xff). - */ -static inline uint32_t mavlink_msg_gimbal_device_information_get_hardware_version(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 16); -} - -/** - * @brief Get field uid from gimbal_device_information message - * - * @return UID of gimbal hardware (0 if unknown). - */ -static inline uint64_t mavlink_msg_gimbal_device_information_get_uid(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field cap_flags from gimbal_device_information message - * - * @return Bitmap of gimbal capability flags. - */ -static inline uint16_t mavlink_msg_gimbal_device_information_get_cap_flags(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 44); -} - -/** - * @brief Get field custom_cap_flags from gimbal_device_information message - * - * @return Bitmap for use for gimbal-specific capability flags. - */ -static inline uint16_t mavlink_msg_gimbal_device_information_get_custom_cap_flags(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 46); -} - -/** - * @brief Get field roll_min from gimbal_device_information message - * - * @return [rad] Minimum hardware roll angle (positive: rolling to the right, negative: rolling to the left). NAN if unknown. - */ -static inline float mavlink_msg_gimbal_device_information_get_roll_min(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Get field roll_max from gimbal_device_information message - * - * @return [rad] Maximum hardware roll angle (positive: rolling to the right, negative: rolling to the left). NAN if unknown. - */ -static inline float mavlink_msg_gimbal_device_information_get_roll_max(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Get field pitch_min from gimbal_device_information message - * - * @return [rad] Minimum hardware pitch angle (positive: up, negative: down). NAN if unknown. - */ -static inline float mavlink_msg_gimbal_device_information_get_pitch_min(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 28); -} - -/** - * @brief Get field pitch_max from gimbal_device_information message - * - * @return [rad] Maximum hardware pitch angle (positive: up, negative: down). NAN if unknown. - */ -static inline float mavlink_msg_gimbal_device_information_get_pitch_max(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 32); -} - -/** - * @brief Get field yaw_min from gimbal_device_information message - * - * @return [rad] Minimum hardware yaw angle (positive: to the right, negative: to the left). NAN if unknown. - */ -static inline float mavlink_msg_gimbal_device_information_get_yaw_min(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 36); -} - -/** - * @brief Get field yaw_max from gimbal_device_information message - * - * @return [rad] Maximum hardware yaw angle (positive: to the right, negative: to the left). NAN if unknown. - */ -static inline float mavlink_msg_gimbal_device_information_get_yaw_max(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 40); -} - -/** - * @brief Get field gimbal_device_id from gimbal_device_information message - * - * @return This field is to be used if the gimbal manager and the gimbal device are the same component and hence have the same component ID. This field is then set to a number between 1-6. If the component ID is separate, this field is not required and must be set to 0. - */ -static inline uint8_t mavlink_msg_gimbal_device_information_get_gimbal_device_id(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 144); -} - -/** - * @brief Decode a gimbal_device_information message into a struct - * - * @param msg The message to decode - * @param gimbal_device_information C-struct to decode the message contents into - */ -static inline void mavlink_msg_gimbal_device_information_decode(const mavlink_message_t* msg, mavlink_gimbal_device_information_t* gimbal_device_information) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - gimbal_device_information->uid = mavlink_msg_gimbal_device_information_get_uid(msg); - gimbal_device_information->time_boot_ms = mavlink_msg_gimbal_device_information_get_time_boot_ms(msg); - gimbal_device_information->firmware_version = mavlink_msg_gimbal_device_information_get_firmware_version(msg); - gimbal_device_information->hardware_version = mavlink_msg_gimbal_device_information_get_hardware_version(msg); - gimbal_device_information->roll_min = mavlink_msg_gimbal_device_information_get_roll_min(msg); - gimbal_device_information->roll_max = mavlink_msg_gimbal_device_information_get_roll_max(msg); - gimbal_device_information->pitch_min = mavlink_msg_gimbal_device_information_get_pitch_min(msg); - gimbal_device_information->pitch_max = mavlink_msg_gimbal_device_information_get_pitch_max(msg); - gimbal_device_information->yaw_min = mavlink_msg_gimbal_device_information_get_yaw_min(msg); - gimbal_device_information->yaw_max = mavlink_msg_gimbal_device_information_get_yaw_max(msg); - gimbal_device_information->cap_flags = mavlink_msg_gimbal_device_information_get_cap_flags(msg); - gimbal_device_information->custom_cap_flags = mavlink_msg_gimbal_device_information_get_custom_cap_flags(msg); - mavlink_msg_gimbal_device_information_get_vendor_name(msg, gimbal_device_information->vendor_name); - mavlink_msg_gimbal_device_information_get_model_name(msg, gimbal_device_information->model_name); - mavlink_msg_gimbal_device_information_get_custom_name(msg, gimbal_device_information->custom_name); - gimbal_device_information->gimbal_device_id = mavlink_msg_gimbal_device_information_get_gimbal_device_id(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION_LEN? msg->len : MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION_LEN; - memset(gimbal_device_information, 0, MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION_LEN); - memcpy(gimbal_device_information, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_gimbal_device_set_attitude.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_gimbal_device_set_attitude.h deleted file mode 100644 index 8685be65..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_gimbal_device_set_attitude.h +++ /dev/null @@ -1,355 +0,0 @@ -#pragma once -// MESSAGE GIMBAL_DEVICE_SET_ATTITUDE PACKING - -#define MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_ATTITUDE 284 - - -typedef struct __mavlink_gimbal_device_set_attitude_t { - float q[4]; /*< Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation). The frame is described in the message description. Set fields to NaN to be ignored.*/ - float angular_velocity_x; /*< [rad/s] X component of angular velocity (positive: rolling to the right). The frame is described in the message description. NaN to be ignored.*/ - float angular_velocity_y; /*< [rad/s] Y component of angular velocity (positive: pitching up). The frame is described in the message description. NaN to be ignored.*/ - float angular_velocity_z; /*< [rad/s] Z component of angular velocity (positive: yawing to the right). The frame is described in the message description. NaN to be ignored.*/ - uint16_t flags; /*< Low level gimbal flags.*/ - uint8_t target_system; /*< System ID*/ - uint8_t target_component; /*< Component ID*/ -} mavlink_gimbal_device_set_attitude_t; - -#define MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_ATTITUDE_LEN 32 -#define MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_ATTITUDE_MIN_LEN 32 -#define MAVLINK_MSG_ID_284_LEN 32 -#define MAVLINK_MSG_ID_284_MIN_LEN 32 - -#define MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_ATTITUDE_CRC 99 -#define MAVLINK_MSG_ID_284_CRC 99 - -#define MAVLINK_MSG_GIMBAL_DEVICE_SET_ATTITUDE_FIELD_Q_LEN 4 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_GIMBAL_DEVICE_SET_ATTITUDE { \ - 284, \ - "GIMBAL_DEVICE_SET_ATTITUDE", \ - 7, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_gimbal_device_set_attitude_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_gimbal_device_set_attitude_t, target_component) }, \ - { "flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_gimbal_device_set_attitude_t, flags) }, \ - { "q", NULL, MAVLINK_TYPE_FLOAT, 4, 0, offsetof(mavlink_gimbal_device_set_attitude_t, q) }, \ - { "angular_velocity_x", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_gimbal_device_set_attitude_t, angular_velocity_x) }, \ - { "angular_velocity_y", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_gimbal_device_set_attitude_t, angular_velocity_y) }, \ - { "angular_velocity_z", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_gimbal_device_set_attitude_t, angular_velocity_z) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_GIMBAL_DEVICE_SET_ATTITUDE { \ - "GIMBAL_DEVICE_SET_ATTITUDE", \ - 7, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_gimbal_device_set_attitude_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_gimbal_device_set_attitude_t, target_component) }, \ - { "flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_gimbal_device_set_attitude_t, flags) }, \ - { "q", NULL, MAVLINK_TYPE_FLOAT, 4, 0, offsetof(mavlink_gimbal_device_set_attitude_t, q) }, \ - { "angular_velocity_x", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_gimbal_device_set_attitude_t, angular_velocity_x) }, \ - { "angular_velocity_y", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_gimbal_device_set_attitude_t, angular_velocity_y) }, \ - { "angular_velocity_z", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_gimbal_device_set_attitude_t, angular_velocity_z) }, \ - } \ -} -#endif - -/** - * @brief Pack a gimbal_device_set_attitude message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID - * @param target_component Component ID - * @param flags Low level gimbal flags. - * @param q Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation). The frame is described in the message description. Set fields to NaN to be ignored. - * @param angular_velocity_x [rad/s] X component of angular velocity (positive: rolling to the right). The frame is described in the message description. NaN to be ignored. - * @param angular_velocity_y [rad/s] Y component of angular velocity (positive: pitching up). The frame is described in the message description. NaN to be ignored. - * @param angular_velocity_z [rad/s] Z component of angular velocity (positive: yawing to the right). The frame is described in the message description. NaN to be ignored. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_gimbal_device_set_attitude_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component, uint16_t flags, const float *q, float angular_velocity_x, float angular_velocity_y, float angular_velocity_z) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_ATTITUDE_LEN]; - _mav_put_float(buf, 16, angular_velocity_x); - _mav_put_float(buf, 20, angular_velocity_y); - _mav_put_float(buf, 24, angular_velocity_z); - _mav_put_uint16_t(buf, 28, flags); - _mav_put_uint8_t(buf, 30, target_system); - _mav_put_uint8_t(buf, 31, target_component); - _mav_put_float_array(buf, 0, q, 4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_ATTITUDE_LEN); -#else - mavlink_gimbal_device_set_attitude_t packet; - packet.angular_velocity_x = angular_velocity_x; - packet.angular_velocity_y = angular_velocity_y; - packet.angular_velocity_z = angular_velocity_z; - packet.flags = flags; - packet.target_system = target_system; - packet.target_component = target_component; - mav_array_memcpy(packet.q, q, sizeof(float)*4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_ATTITUDE_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_ATTITUDE; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_ATTITUDE_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_ATTITUDE_LEN, MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_ATTITUDE_CRC); -} - -/** - * @brief Pack a gimbal_device_set_attitude message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @param flags Low level gimbal flags. - * @param q Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation). The frame is described in the message description. Set fields to NaN to be ignored. - * @param angular_velocity_x [rad/s] X component of angular velocity (positive: rolling to the right). The frame is described in the message description. NaN to be ignored. - * @param angular_velocity_y [rad/s] Y component of angular velocity (positive: pitching up). The frame is described in the message description. NaN to be ignored. - * @param angular_velocity_z [rad/s] Z component of angular velocity (positive: yawing to the right). The frame is described in the message description. NaN to be ignored. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_gimbal_device_set_attitude_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component,uint16_t flags,const float *q,float angular_velocity_x,float angular_velocity_y,float angular_velocity_z) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_ATTITUDE_LEN]; - _mav_put_float(buf, 16, angular_velocity_x); - _mav_put_float(buf, 20, angular_velocity_y); - _mav_put_float(buf, 24, angular_velocity_z); - _mav_put_uint16_t(buf, 28, flags); - _mav_put_uint8_t(buf, 30, target_system); - _mav_put_uint8_t(buf, 31, target_component); - _mav_put_float_array(buf, 0, q, 4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_ATTITUDE_LEN); -#else - mavlink_gimbal_device_set_attitude_t packet; - packet.angular_velocity_x = angular_velocity_x; - packet.angular_velocity_y = angular_velocity_y; - packet.angular_velocity_z = angular_velocity_z; - packet.flags = flags; - packet.target_system = target_system; - packet.target_component = target_component; - mav_array_memcpy(packet.q, q, sizeof(float)*4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_ATTITUDE_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_ATTITUDE; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_ATTITUDE_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_ATTITUDE_LEN, MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_ATTITUDE_CRC); -} - -/** - * @brief Encode a gimbal_device_set_attitude struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param gimbal_device_set_attitude C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_gimbal_device_set_attitude_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gimbal_device_set_attitude_t* gimbal_device_set_attitude) -{ - return mavlink_msg_gimbal_device_set_attitude_pack(system_id, component_id, msg, gimbal_device_set_attitude->target_system, gimbal_device_set_attitude->target_component, gimbal_device_set_attitude->flags, gimbal_device_set_attitude->q, gimbal_device_set_attitude->angular_velocity_x, gimbal_device_set_attitude->angular_velocity_y, gimbal_device_set_attitude->angular_velocity_z); -} - -/** - * @brief Encode a gimbal_device_set_attitude struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param gimbal_device_set_attitude C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_gimbal_device_set_attitude_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_gimbal_device_set_attitude_t* gimbal_device_set_attitude) -{ - return mavlink_msg_gimbal_device_set_attitude_pack_chan(system_id, component_id, chan, msg, gimbal_device_set_attitude->target_system, gimbal_device_set_attitude->target_component, gimbal_device_set_attitude->flags, gimbal_device_set_attitude->q, gimbal_device_set_attitude->angular_velocity_x, gimbal_device_set_attitude->angular_velocity_y, gimbal_device_set_attitude->angular_velocity_z); -} - -/** - * @brief Send a gimbal_device_set_attitude message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param target_component Component ID - * @param flags Low level gimbal flags. - * @param q Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation). The frame is described in the message description. Set fields to NaN to be ignored. - * @param angular_velocity_x [rad/s] X component of angular velocity (positive: rolling to the right). The frame is described in the message description. NaN to be ignored. - * @param angular_velocity_y [rad/s] Y component of angular velocity (positive: pitching up). The frame is described in the message description. NaN to be ignored. - * @param angular_velocity_z [rad/s] Z component of angular velocity (positive: yawing to the right). The frame is described in the message description. NaN to be ignored. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_gimbal_device_set_attitude_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t flags, const float *q, float angular_velocity_x, float angular_velocity_y, float angular_velocity_z) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_ATTITUDE_LEN]; - _mav_put_float(buf, 16, angular_velocity_x); - _mav_put_float(buf, 20, angular_velocity_y); - _mav_put_float(buf, 24, angular_velocity_z); - _mav_put_uint16_t(buf, 28, flags); - _mav_put_uint8_t(buf, 30, target_system); - _mav_put_uint8_t(buf, 31, target_component); - _mav_put_float_array(buf, 0, q, 4); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_ATTITUDE, buf, MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_ATTITUDE_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_ATTITUDE_LEN, MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_ATTITUDE_CRC); -#else - mavlink_gimbal_device_set_attitude_t packet; - packet.angular_velocity_x = angular_velocity_x; - packet.angular_velocity_y = angular_velocity_y; - packet.angular_velocity_z = angular_velocity_z; - packet.flags = flags; - packet.target_system = target_system; - packet.target_component = target_component; - mav_array_memcpy(packet.q, q, sizeof(float)*4); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_ATTITUDE, (const char *)&packet, MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_ATTITUDE_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_ATTITUDE_LEN, MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_ATTITUDE_CRC); -#endif -} - -/** - * @brief Send a gimbal_device_set_attitude message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_gimbal_device_set_attitude_send_struct(mavlink_channel_t chan, const mavlink_gimbal_device_set_attitude_t* gimbal_device_set_attitude) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_gimbal_device_set_attitude_send(chan, gimbal_device_set_attitude->target_system, gimbal_device_set_attitude->target_component, gimbal_device_set_attitude->flags, gimbal_device_set_attitude->q, gimbal_device_set_attitude->angular_velocity_x, gimbal_device_set_attitude->angular_velocity_y, gimbal_device_set_attitude->angular_velocity_z); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_ATTITUDE, (const char *)gimbal_device_set_attitude, MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_ATTITUDE_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_ATTITUDE_LEN, MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_ATTITUDE_CRC); -#endif -} - -#if MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_ATTITUDE_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_gimbal_device_set_attitude_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t flags, const float *q, float angular_velocity_x, float angular_velocity_y, float angular_velocity_z) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_float(buf, 16, angular_velocity_x); - _mav_put_float(buf, 20, angular_velocity_y); - _mav_put_float(buf, 24, angular_velocity_z); - _mav_put_uint16_t(buf, 28, flags); - _mav_put_uint8_t(buf, 30, target_system); - _mav_put_uint8_t(buf, 31, target_component); - _mav_put_float_array(buf, 0, q, 4); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_ATTITUDE, buf, MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_ATTITUDE_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_ATTITUDE_LEN, MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_ATTITUDE_CRC); -#else - mavlink_gimbal_device_set_attitude_t *packet = (mavlink_gimbal_device_set_attitude_t *)msgbuf; - packet->angular_velocity_x = angular_velocity_x; - packet->angular_velocity_y = angular_velocity_y; - packet->angular_velocity_z = angular_velocity_z; - packet->flags = flags; - packet->target_system = target_system; - packet->target_component = target_component; - mav_array_memcpy(packet->q, q, sizeof(float)*4); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_ATTITUDE, (const char *)packet, MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_ATTITUDE_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_ATTITUDE_LEN, MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_ATTITUDE_CRC); -#endif -} -#endif - -#endif - -// MESSAGE GIMBAL_DEVICE_SET_ATTITUDE UNPACKING - - -/** - * @brief Get field target_system from gimbal_device_set_attitude message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_gimbal_device_set_attitude_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 30); -} - -/** - * @brief Get field target_component from gimbal_device_set_attitude message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_gimbal_device_set_attitude_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 31); -} - -/** - * @brief Get field flags from gimbal_device_set_attitude message - * - * @return Low level gimbal flags. - */ -static inline uint16_t mavlink_msg_gimbal_device_set_attitude_get_flags(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 28); -} - -/** - * @brief Get field q from gimbal_device_set_attitude message - * - * @return Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation). The frame is described in the message description. Set fields to NaN to be ignored. - */ -static inline uint16_t mavlink_msg_gimbal_device_set_attitude_get_q(const mavlink_message_t* msg, float *q) -{ - return _MAV_RETURN_float_array(msg, q, 4, 0); -} - -/** - * @brief Get field angular_velocity_x from gimbal_device_set_attitude message - * - * @return [rad/s] X component of angular velocity (positive: rolling to the right). The frame is described in the message description. NaN to be ignored. - */ -static inline float mavlink_msg_gimbal_device_set_attitude_get_angular_velocity_x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field angular_velocity_y from gimbal_device_set_attitude message - * - * @return [rad/s] Y component of angular velocity (positive: pitching up). The frame is described in the message description. NaN to be ignored. - */ -static inline float mavlink_msg_gimbal_device_set_attitude_get_angular_velocity_y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Get field angular_velocity_z from gimbal_device_set_attitude message - * - * @return [rad/s] Z component of angular velocity (positive: yawing to the right). The frame is described in the message description. NaN to be ignored. - */ -static inline float mavlink_msg_gimbal_device_set_attitude_get_angular_velocity_z(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Decode a gimbal_device_set_attitude message into a struct - * - * @param msg The message to decode - * @param gimbal_device_set_attitude C-struct to decode the message contents into - */ -static inline void mavlink_msg_gimbal_device_set_attitude_decode(const mavlink_message_t* msg, mavlink_gimbal_device_set_attitude_t* gimbal_device_set_attitude) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_gimbal_device_set_attitude_get_q(msg, gimbal_device_set_attitude->q); - gimbal_device_set_attitude->angular_velocity_x = mavlink_msg_gimbal_device_set_attitude_get_angular_velocity_x(msg); - gimbal_device_set_attitude->angular_velocity_y = mavlink_msg_gimbal_device_set_attitude_get_angular_velocity_y(msg); - gimbal_device_set_attitude->angular_velocity_z = mavlink_msg_gimbal_device_set_attitude_get_angular_velocity_z(msg); - gimbal_device_set_attitude->flags = mavlink_msg_gimbal_device_set_attitude_get_flags(msg); - gimbal_device_set_attitude->target_system = mavlink_msg_gimbal_device_set_attitude_get_target_system(msg); - gimbal_device_set_attitude->target_component = mavlink_msg_gimbal_device_set_attitude_get_target_component(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_ATTITUDE_LEN? msg->len : MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_ATTITUDE_LEN; - memset(gimbal_device_set_attitude, 0, MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_ATTITUDE_LEN); - memcpy(gimbal_device_set_attitude, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_gimbal_manager_information.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_gimbal_manager_information.h deleted file mode 100644 index f0d403ca..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_gimbal_manager_information.h +++ /dev/null @@ -1,413 +0,0 @@ -#pragma once -// MESSAGE GIMBAL_MANAGER_INFORMATION PACKING - -#define MAVLINK_MSG_ID_GIMBAL_MANAGER_INFORMATION 280 - - -typedef struct __mavlink_gimbal_manager_information_t { - uint32_t time_boot_ms; /*< [ms] Timestamp (time since system boot).*/ - uint32_t cap_flags; /*< Bitmap of gimbal capability flags.*/ - float roll_min; /*< [rad] Minimum hardware roll angle (positive: rolling to the right, negative: rolling to the left)*/ - float roll_max; /*< [rad] Maximum hardware roll angle (positive: rolling to the right, negative: rolling to the left)*/ - float pitch_min; /*< [rad] Minimum pitch angle (positive: up, negative: down)*/ - float pitch_max; /*< [rad] Maximum pitch angle (positive: up, negative: down)*/ - float yaw_min; /*< [rad] Minimum yaw angle (positive: to the right, negative: to the left)*/ - float yaw_max; /*< [rad] Maximum yaw angle (positive: to the right, negative: to the left)*/ - uint8_t gimbal_device_id; /*< Gimbal device ID that this gimbal manager is responsible for. Component ID of gimbal device (or 1-6 for non-MAVLink gimbal).*/ -} mavlink_gimbal_manager_information_t; - -#define MAVLINK_MSG_ID_GIMBAL_MANAGER_INFORMATION_LEN 33 -#define MAVLINK_MSG_ID_GIMBAL_MANAGER_INFORMATION_MIN_LEN 33 -#define MAVLINK_MSG_ID_280_LEN 33 -#define MAVLINK_MSG_ID_280_MIN_LEN 33 - -#define MAVLINK_MSG_ID_GIMBAL_MANAGER_INFORMATION_CRC 70 -#define MAVLINK_MSG_ID_280_CRC 70 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_GIMBAL_MANAGER_INFORMATION { \ - 280, \ - "GIMBAL_MANAGER_INFORMATION", \ - 9, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_gimbal_manager_information_t, time_boot_ms) }, \ - { "cap_flags", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_gimbal_manager_information_t, cap_flags) }, \ - { "gimbal_device_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_gimbal_manager_information_t, gimbal_device_id) }, \ - { "roll_min", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_gimbal_manager_information_t, roll_min) }, \ - { "roll_max", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_gimbal_manager_information_t, roll_max) }, \ - { "pitch_min", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_gimbal_manager_information_t, pitch_min) }, \ - { "pitch_max", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_gimbal_manager_information_t, pitch_max) }, \ - { "yaw_min", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_gimbal_manager_information_t, yaw_min) }, \ - { "yaw_max", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_gimbal_manager_information_t, yaw_max) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_GIMBAL_MANAGER_INFORMATION { \ - "GIMBAL_MANAGER_INFORMATION", \ - 9, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_gimbal_manager_information_t, time_boot_ms) }, \ - { "cap_flags", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_gimbal_manager_information_t, cap_flags) }, \ - { "gimbal_device_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_gimbal_manager_information_t, gimbal_device_id) }, \ - { "roll_min", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_gimbal_manager_information_t, roll_min) }, \ - { "roll_max", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_gimbal_manager_information_t, roll_max) }, \ - { "pitch_min", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_gimbal_manager_information_t, pitch_min) }, \ - { "pitch_max", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_gimbal_manager_information_t, pitch_max) }, \ - { "yaw_min", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_gimbal_manager_information_t, yaw_min) }, \ - { "yaw_max", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_gimbal_manager_information_t, yaw_max) }, \ - } \ -} -#endif - -/** - * @brief Pack a gimbal_manager_information message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param time_boot_ms [ms] Timestamp (time since system boot). - * @param cap_flags Bitmap of gimbal capability flags. - * @param gimbal_device_id Gimbal device ID that this gimbal manager is responsible for. Component ID of gimbal device (or 1-6 for non-MAVLink gimbal). - * @param roll_min [rad] Minimum hardware roll angle (positive: rolling to the right, negative: rolling to the left) - * @param roll_max [rad] Maximum hardware roll angle (positive: rolling to the right, negative: rolling to the left) - * @param pitch_min [rad] Minimum pitch angle (positive: up, negative: down) - * @param pitch_max [rad] Maximum pitch angle (positive: up, negative: down) - * @param yaw_min [rad] Minimum yaw angle (positive: to the right, negative: to the left) - * @param yaw_max [rad] Maximum yaw angle (positive: to the right, negative: to the left) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_gimbal_manager_information_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint32_t time_boot_ms, uint32_t cap_flags, uint8_t gimbal_device_id, float roll_min, float roll_max, float pitch_min, float pitch_max, float yaw_min, float yaw_max) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_GIMBAL_MANAGER_INFORMATION_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_uint32_t(buf, 4, cap_flags); - _mav_put_float(buf, 8, roll_min); - _mav_put_float(buf, 12, roll_max); - _mav_put_float(buf, 16, pitch_min); - _mav_put_float(buf, 20, pitch_max); - _mav_put_float(buf, 24, yaw_min); - _mav_put_float(buf, 28, yaw_max); - _mav_put_uint8_t(buf, 32, gimbal_device_id); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GIMBAL_MANAGER_INFORMATION_LEN); -#else - mavlink_gimbal_manager_information_t packet; - packet.time_boot_ms = time_boot_ms; - packet.cap_flags = cap_flags; - packet.roll_min = roll_min; - packet.roll_max = roll_max; - packet.pitch_min = pitch_min; - packet.pitch_max = pitch_max; - packet.yaw_min = yaw_min; - packet.yaw_max = yaw_max; - packet.gimbal_device_id = gimbal_device_id; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GIMBAL_MANAGER_INFORMATION_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_GIMBAL_MANAGER_INFORMATION; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GIMBAL_MANAGER_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_INFORMATION_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_INFORMATION_CRC); -} - -/** - * @brief Pack a gimbal_manager_information message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_boot_ms [ms] Timestamp (time since system boot). - * @param cap_flags Bitmap of gimbal capability flags. - * @param gimbal_device_id Gimbal device ID that this gimbal manager is responsible for. Component ID of gimbal device (or 1-6 for non-MAVLink gimbal). - * @param roll_min [rad] Minimum hardware roll angle (positive: rolling to the right, negative: rolling to the left) - * @param roll_max [rad] Maximum hardware roll angle (positive: rolling to the right, negative: rolling to the left) - * @param pitch_min [rad] Minimum pitch angle (positive: up, negative: down) - * @param pitch_max [rad] Maximum pitch angle (positive: up, negative: down) - * @param yaw_min [rad] Minimum yaw angle (positive: to the right, negative: to the left) - * @param yaw_max [rad] Maximum yaw angle (positive: to the right, negative: to the left) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_gimbal_manager_information_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint32_t time_boot_ms,uint32_t cap_flags,uint8_t gimbal_device_id,float roll_min,float roll_max,float pitch_min,float pitch_max,float yaw_min,float yaw_max) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_GIMBAL_MANAGER_INFORMATION_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_uint32_t(buf, 4, cap_flags); - _mav_put_float(buf, 8, roll_min); - _mav_put_float(buf, 12, roll_max); - _mav_put_float(buf, 16, pitch_min); - _mav_put_float(buf, 20, pitch_max); - _mav_put_float(buf, 24, yaw_min); - _mav_put_float(buf, 28, yaw_max); - _mav_put_uint8_t(buf, 32, gimbal_device_id); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GIMBAL_MANAGER_INFORMATION_LEN); -#else - mavlink_gimbal_manager_information_t packet; - packet.time_boot_ms = time_boot_ms; - packet.cap_flags = cap_flags; - packet.roll_min = roll_min; - packet.roll_max = roll_max; - packet.pitch_min = pitch_min; - packet.pitch_max = pitch_max; - packet.yaw_min = yaw_min; - packet.yaw_max = yaw_max; - packet.gimbal_device_id = gimbal_device_id; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GIMBAL_MANAGER_INFORMATION_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_GIMBAL_MANAGER_INFORMATION; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GIMBAL_MANAGER_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_INFORMATION_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_INFORMATION_CRC); -} - -/** - * @brief Encode a gimbal_manager_information struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param gimbal_manager_information C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_gimbal_manager_information_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gimbal_manager_information_t* gimbal_manager_information) -{ - return mavlink_msg_gimbal_manager_information_pack(system_id, component_id, msg, gimbal_manager_information->time_boot_ms, gimbal_manager_information->cap_flags, gimbal_manager_information->gimbal_device_id, gimbal_manager_information->roll_min, gimbal_manager_information->roll_max, gimbal_manager_information->pitch_min, gimbal_manager_information->pitch_max, gimbal_manager_information->yaw_min, gimbal_manager_information->yaw_max); -} - -/** - * @brief Encode a gimbal_manager_information struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param gimbal_manager_information C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_gimbal_manager_information_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_gimbal_manager_information_t* gimbal_manager_information) -{ - return mavlink_msg_gimbal_manager_information_pack_chan(system_id, component_id, chan, msg, gimbal_manager_information->time_boot_ms, gimbal_manager_information->cap_flags, gimbal_manager_information->gimbal_device_id, gimbal_manager_information->roll_min, gimbal_manager_information->roll_max, gimbal_manager_information->pitch_min, gimbal_manager_information->pitch_max, gimbal_manager_information->yaw_min, gimbal_manager_information->yaw_max); -} - -/** - * @brief Send a gimbal_manager_information message - * @param chan MAVLink channel to send the message - * - * @param time_boot_ms [ms] Timestamp (time since system boot). - * @param cap_flags Bitmap of gimbal capability flags. - * @param gimbal_device_id Gimbal device ID that this gimbal manager is responsible for. Component ID of gimbal device (or 1-6 for non-MAVLink gimbal). - * @param roll_min [rad] Minimum hardware roll angle (positive: rolling to the right, negative: rolling to the left) - * @param roll_max [rad] Maximum hardware roll angle (positive: rolling to the right, negative: rolling to the left) - * @param pitch_min [rad] Minimum pitch angle (positive: up, negative: down) - * @param pitch_max [rad] Maximum pitch angle (positive: up, negative: down) - * @param yaw_min [rad] Minimum yaw angle (positive: to the right, negative: to the left) - * @param yaw_max [rad] Maximum yaw angle (positive: to the right, negative: to the left) - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_gimbal_manager_information_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint32_t cap_flags, uint8_t gimbal_device_id, float roll_min, float roll_max, float pitch_min, float pitch_max, float yaw_min, float yaw_max) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_GIMBAL_MANAGER_INFORMATION_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_uint32_t(buf, 4, cap_flags); - _mav_put_float(buf, 8, roll_min); - _mav_put_float(buf, 12, roll_max); - _mav_put_float(buf, 16, pitch_min); - _mav_put_float(buf, 20, pitch_max); - _mav_put_float(buf, 24, yaw_min); - _mav_put_float(buf, 28, yaw_max); - _mav_put_uint8_t(buf, 32, gimbal_device_id); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_MANAGER_INFORMATION, buf, MAVLINK_MSG_ID_GIMBAL_MANAGER_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_INFORMATION_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_INFORMATION_CRC); -#else - mavlink_gimbal_manager_information_t packet; - packet.time_boot_ms = time_boot_ms; - packet.cap_flags = cap_flags; - packet.roll_min = roll_min; - packet.roll_max = roll_max; - packet.pitch_min = pitch_min; - packet.pitch_max = pitch_max; - packet.yaw_min = yaw_min; - packet.yaw_max = yaw_max; - packet.gimbal_device_id = gimbal_device_id; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_MANAGER_INFORMATION, (const char *)&packet, MAVLINK_MSG_ID_GIMBAL_MANAGER_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_INFORMATION_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_INFORMATION_CRC); -#endif -} - -/** - * @brief Send a gimbal_manager_information message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_gimbal_manager_information_send_struct(mavlink_channel_t chan, const mavlink_gimbal_manager_information_t* gimbal_manager_information) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_gimbal_manager_information_send(chan, gimbal_manager_information->time_boot_ms, gimbal_manager_information->cap_flags, gimbal_manager_information->gimbal_device_id, gimbal_manager_information->roll_min, gimbal_manager_information->roll_max, gimbal_manager_information->pitch_min, gimbal_manager_information->pitch_max, gimbal_manager_information->yaw_min, gimbal_manager_information->yaw_max); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_MANAGER_INFORMATION, (const char *)gimbal_manager_information, MAVLINK_MSG_ID_GIMBAL_MANAGER_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_INFORMATION_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_INFORMATION_CRC); -#endif -} - -#if MAVLINK_MSG_ID_GIMBAL_MANAGER_INFORMATION_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_gimbal_manager_information_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint32_t cap_flags, uint8_t gimbal_device_id, float roll_min, float roll_max, float pitch_min, float pitch_max, float yaw_min, float yaw_max) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_uint32_t(buf, 4, cap_flags); - _mav_put_float(buf, 8, roll_min); - _mav_put_float(buf, 12, roll_max); - _mav_put_float(buf, 16, pitch_min); - _mav_put_float(buf, 20, pitch_max); - _mav_put_float(buf, 24, yaw_min); - _mav_put_float(buf, 28, yaw_max); - _mav_put_uint8_t(buf, 32, gimbal_device_id); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_MANAGER_INFORMATION, buf, MAVLINK_MSG_ID_GIMBAL_MANAGER_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_INFORMATION_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_INFORMATION_CRC); -#else - mavlink_gimbal_manager_information_t *packet = (mavlink_gimbal_manager_information_t *)msgbuf; - packet->time_boot_ms = time_boot_ms; - packet->cap_flags = cap_flags; - packet->roll_min = roll_min; - packet->roll_max = roll_max; - packet->pitch_min = pitch_min; - packet->pitch_max = pitch_max; - packet->yaw_min = yaw_min; - packet->yaw_max = yaw_max; - packet->gimbal_device_id = gimbal_device_id; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_MANAGER_INFORMATION, (const char *)packet, MAVLINK_MSG_ID_GIMBAL_MANAGER_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_INFORMATION_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_INFORMATION_CRC); -#endif -} -#endif - -#endif - -// MESSAGE GIMBAL_MANAGER_INFORMATION UNPACKING - - -/** - * @brief Get field time_boot_ms from gimbal_manager_information message - * - * @return [ms] Timestamp (time since system boot). - */ -static inline uint32_t mavlink_msg_gimbal_manager_information_get_time_boot_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field cap_flags from gimbal_manager_information message - * - * @return Bitmap of gimbal capability flags. - */ -static inline uint32_t mavlink_msg_gimbal_manager_information_get_cap_flags(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 4); -} - -/** - * @brief Get field gimbal_device_id from gimbal_manager_information message - * - * @return Gimbal device ID that this gimbal manager is responsible for. Component ID of gimbal device (or 1-6 for non-MAVLink gimbal). - */ -static inline uint8_t mavlink_msg_gimbal_manager_information_get_gimbal_device_id(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 32); -} - -/** - * @brief Get field roll_min from gimbal_manager_information message - * - * @return [rad] Minimum hardware roll angle (positive: rolling to the right, negative: rolling to the left) - */ -static inline float mavlink_msg_gimbal_manager_information_get_roll_min(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field roll_max from gimbal_manager_information message - * - * @return [rad] Maximum hardware roll angle (positive: rolling to the right, negative: rolling to the left) - */ -static inline float mavlink_msg_gimbal_manager_information_get_roll_max(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field pitch_min from gimbal_manager_information message - * - * @return [rad] Minimum pitch angle (positive: up, negative: down) - */ -static inline float mavlink_msg_gimbal_manager_information_get_pitch_min(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field pitch_max from gimbal_manager_information message - * - * @return [rad] Maximum pitch angle (positive: up, negative: down) - */ -static inline float mavlink_msg_gimbal_manager_information_get_pitch_max(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Get field yaw_min from gimbal_manager_information message - * - * @return [rad] Minimum yaw angle (positive: to the right, negative: to the left) - */ -static inline float mavlink_msg_gimbal_manager_information_get_yaw_min(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Get field yaw_max from gimbal_manager_information message - * - * @return [rad] Maximum yaw angle (positive: to the right, negative: to the left) - */ -static inline float mavlink_msg_gimbal_manager_information_get_yaw_max(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 28); -} - -/** - * @brief Decode a gimbal_manager_information message into a struct - * - * @param msg The message to decode - * @param gimbal_manager_information C-struct to decode the message contents into - */ -static inline void mavlink_msg_gimbal_manager_information_decode(const mavlink_message_t* msg, mavlink_gimbal_manager_information_t* gimbal_manager_information) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - gimbal_manager_information->time_boot_ms = mavlink_msg_gimbal_manager_information_get_time_boot_ms(msg); - gimbal_manager_information->cap_flags = mavlink_msg_gimbal_manager_information_get_cap_flags(msg); - gimbal_manager_information->roll_min = mavlink_msg_gimbal_manager_information_get_roll_min(msg); - gimbal_manager_information->roll_max = mavlink_msg_gimbal_manager_information_get_roll_max(msg); - gimbal_manager_information->pitch_min = mavlink_msg_gimbal_manager_information_get_pitch_min(msg); - gimbal_manager_information->pitch_max = mavlink_msg_gimbal_manager_information_get_pitch_max(msg); - gimbal_manager_information->yaw_min = mavlink_msg_gimbal_manager_information_get_yaw_min(msg); - gimbal_manager_information->yaw_max = mavlink_msg_gimbal_manager_information_get_yaw_max(msg); - gimbal_manager_information->gimbal_device_id = mavlink_msg_gimbal_manager_information_get_gimbal_device_id(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_GIMBAL_MANAGER_INFORMATION_LEN? msg->len : MAVLINK_MSG_ID_GIMBAL_MANAGER_INFORMATION_LEN; - memset(gimbal_manager_information, 0, MAVLINK_MSG_ID_GIMBAL_MANAGER_INFORMATION_LEN); - memcpy(gimbal_manager_information, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_gimbal_manager_set_attitude.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_gimbal_manager_set_attitude.h deleted file mode 100644 index 8ae53b27..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_gimbal_manager_set_attitude.h +++ /dev/null @@ -1,380 +0,0 @@ -#pragma once -// MESSAGE GIMBAL_MANAGER_SET_ATTITUDE PACKING - -#define MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE 282 - - -typedef struct __mavlink_gimbal_manager_set_attitude_t { - uint32_t flags; /*< High level gimbal manager flags to use.*/ - float q[4]; /*< Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation, the frame is depends on whether the flag GIMBAL_MANAGER_FLAGS_YAW_LOCK is set)*/ - float angular_velocity_x; /*< [rad/s] X component of angular velocity, positive is rolling to the right, NaN to be ignored.*/ - float angular_velocity_y; /*< [rad/s] Y component of angular velocity, positive is pitching up, NaN to be ignored.*/ - float angular_velocity_z; /*< [rad/s] Z component of angular velocity, positive is yawing to the right, NaN to be ignored.*/ - uint8_t target_system; /*< System ID*/ - uint8_t target_component; /*< Component ID*/ - uint8_t gimbal_device_id; /*< Component ID of gimbal device to address (or 1-6 for non-MAVLink gimbal), 0 for all gimbal device components. Send command multiple times for more than one gimbal (but not all gimbals).*/ -} mavlink_gimbal_manager_set_attitude_t; - -#define MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE_LEN 35 -#define MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE_MIN_LEN 35 -#define MAVLINK_MSG_ID_282_LEN 35 -#define MAVLINK_MSG_ID_282_MIN_LEN 35 - -#define MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE_CRC 123 -#define MAVLINK_MSG_ID_282_CRC 123 - -#define MAVLINK_MSG_GIMBAL_MANAGER_SET_ATTITUDE_FIELD_Q_LEN 4 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_GIMBAL_MANAGER_SET_ATTITUDE { \ - 282, \ - "GIMBAL_MANAGER_SET_ATTITUDE", \ - 8, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_gimbal_manager_set_attitude_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_gimbal_manager_set_attitude_t, target_component) }, \ - { "flags", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_gimbal_manager_set_attitude_t, flags) }, \ - { "gimbal_device_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_gimbal_manager_set_attitude_t, gimbal_device_id) }, \ - { "q", NULL, MAVLINK_TYPE_FLOAT, 4, 4, offsetof(mavlink_gimbal_manager_set_attitude_t, q) }, \ - { "angular_velocity_x", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_gimbal_manager_set_attitude_t, angular_velocity_x) }, \ - { "angular_velocity_y", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_gimbal_manager_set_attitude_t, angular_velocity_y) }, \ - { "angular_velocity_z", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_gimbal_manager_set_attitude_t, angular_velocity_z) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_GIMBAL_MANAGER_SET_ATTITUDE { \ - "GIMBAL_MANAGER_SET_ATTITUDE", \ - 8, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_gimbal_manager_set_attitude_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_gimbal_manager_set_attitude_t, target_component) }, \ - { "flags", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_gimbal_manager_set_attitude_t, flags) }, \ - { "gimbal_device_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_gimbal_manager_set_attitude_t, gimbal_device_id) }, \ - { "q", NULL, MAVLINK_TYPE_FLOAT, 4, 4, offsetof(mavlink_gimbal_manager_set_attitude_t, q) }, \ - { "angular_velocity_x", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_gimbal_manager_set_attitude_t, angular_velocity_x) }, \ - { "angular_velocity_y", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_gimbal_manager_set_attitude_t, angular_velocity_y) }, \ - { "angular_velocity_z", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_gimbal_manager_set_attitude_t, angular_velocity_z) }, \ - } \ -} -#endif - -/** - * @brief Pack a gimbal_manager_set_attitude message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID - * @param target_component Component ID - * @param flags High level gimbal manager flags to use. - * @param gimbal_device_id Component ID of gimbal device to address (or 1-6 for non-MAVLink gimbal), 0 for all gimbal device components. Send command multiple times for more than one gimbal (but not all gimbals). - * @param q Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation, the frame is depends on whether the flag GIMBAL_MANAGER_FLAGS_YAW_LOCK is set) - * @param angular_velocity_x [rad/s] X component of angular velocity, positive is rolling to the right, NaN to be ignored. - * @param angular_velocity_y [rad/s] Y component of angular velocity, positive is pitching up, NaN to be ignored. - * @param angular_velocity_z [rad/s] Z component of angular velocity, positive is yawing to the right, NaN to be ignored. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_gimbal_manager_set_attitude_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component, uint32_t flags, uint8_t gimbal_device_id, const float *q, float angular_velocity_x, float angular_velocity_y, float angular_velocity_z) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE_LEN]; - _mav_put_uint32_t(buf, 0, flags); - _mav_put_float(buf, 20, angular_velocity_x); - _mav_put_float(buf, 24, angular_velocity_y); - _mav_put_float(buf, 28, angular_velocity_z); - _mav_put_uint8_t(buf, 32, target_system); - _mav_put_uint8_t(buf, 33, target_component); - _mav_put_uint8_t(buf, 34, gimbal_device_id); - _mav_put_float_array(buf, 4, q, 4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE_LEN); -#else - mavlink_gimbal_manager_set_attitude_t packet; - packet.flags = flags; - packet.angular_velocity_x = angular_velocity_x; - packet.angular_velocity_y = angular_velocity_y; - packet.angular_velocity_z = angular_velocity_z; - packet.target_system = target_system; - packet.target_component = target_component; - packet.gimbal_device_id = gimbal_device_id; - mav_array_memcpy(packet.q, q, sizeof(float)*4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE_CRC); -} - -/** - * @brief Pack a gimbal_manager_set_attitude message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @param flags High level gimbal manager flags to use. - * @param gimbal_device_id Component ID of gimbal device to address (or 1-6 for non-MAVLink gimbal), 0 for all gimbal device components. Send command multiple times for more than one gimbal (but not all gimbals). - * @param q Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation, the frame is depends on whether the flag GIMBAL_MANAGER_FLAGS_YAW_LOCK is set) - * @param angular_velocity_x [rad/s] X component of angular velocity, positive is rolling to the right, NaN to be ignored. - * @param angular_velocity_y [rad/s] Y component of angular velocity, positive is pitching up, NaN to be ignored. - * @param angular_velocity_z [rad/s] Z component of angular velocity, positive is yawing to the right, NaN to be ignored. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_gimbal_manager_set_attitude_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component,uint32_t flags,uint8_t gimbal_device_id,const float *q,float angular_velocity_x,float angular_velocity_y,float angular_velocity_z) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE_LEN]; - _mav_put_uint32_t(buf, 0, flags); - _mav_put_float(buf, 20, angular_velocity_x); - _mav_put_float(buf, 24, angular_velocity_y); - _mav_put_float(buf, 28, angular_velocity_z); - _mav_put_uint8_t(buf, 32, target_system); - _mav_put_uint8_t(buf, 33, target_component); - _mav_put_uint8_t(buf, 34, gimbal_device_id); - _mav_put_float_array(buf, 4, q, 4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE_LEN); -#else - mavlink_gimbal_manager_set_attitude_t packet; - packet.flags = flags; - packet.angular_velocity_x = angular_velocity_x; - packet.angular_velocity_y = angular_velocity_y; - packet.angular_velocity_z = angular_velocity_z; - packet.target_system = target_system; - packet.target_component = target_component; - packet.gimbal_device_id = gimbal_device_id; - mav_array_memcpy(packet.q, q, sizeof(float)*4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE_CRC); -} - -/** - * @brief Encode a gimbal_manager_set_attitude struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param gimbal_manager_set_attitude C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_gimbal_manager_set_attitude_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gimbal_manager_set_attitude_t* gimbal_manager_set_attitude) -{ - return mavlink_msg_gimbal_manager_set_attitude_pack(system_id, component_id, msg, gimbal_manager_set_attitude->target_system, gimbal_manager_set_attitude->target_component, gimbal_manager_set_attitude->flags, gimbal_manager_set_attitude->gimbal_device_id, gimbal_manager_set_attitude->q, gimbal_manager_set_attitude->angular_velocity_x, gimbal_manager_set_attitude->angular_velocity_y, gimbal_manager_set_attitude->angular_velocity_z); -} - -/** - * @brief Encode a gimbal_manager_set_attitude struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param gimbal_manager_set_attitude C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_gimbal_manager_set_attitude_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_gimbal_manager_set_attitude_t* gimbal_manager_set_attitude) -{ - return mavlink_msg_gimbal_manager_set_attitude_pack_chan(system_id, component_id, chan, msg, gimbal_manager_set_attitude->target_system, gimbal_manager_set_attitude->target_component, gimbal_manager_set_attitude->flags, gimbal_manager_set_attitude->gimbal_device_id, gimbal_manager_set_attitude->q, gimbal_manager_set_attitude->angular_velocity_x, gimbal_manager_set_attitude->angular_velocity_y, gimbal_manager_set_attitude->angular_velocity_z); -} - -/** - * @brief Send a gimbal_manager_set_attitude message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param target_component Component ID - * @param flags High level gimbal manager flags to use. - * @param gimbal_device_id Component ID of gimbal device to address (or 1-6 for non-MAVLink gimbal), 0 for all gimbal device components. Send command multiple times for more than one gimbal (but not all gimbals). - * @param q Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation, the frame is depends on whether the flag GIMBAL_MANAGER_FLAGS_YAW_LOCK is set) - * @param angular_velocity_x [rad/s] X component of angular velocity, positive is rolling to the right, NaN to be ignored. - * @param angular_velocity_y [rad/s] Y component of angular velocity, positive is pitching up, NaN to be ignored. - * @param angular_velocity_z [rad/s] Z component of angular velocity, positive is yawing to the right, NaN to be ignored. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_gimbal_manager_set_attitude_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint32_t flags, uint8_t gimbal_device_id, const float *q, float angular_velocity_x, float angular_velocity_y, float angular_velocity_z) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE_LEN]; - _mav_put_uint32_t(buf, 0, flags); - _mav_put_float(buf, 20, angular_velocity_x); - _mav_put_float(buf, 24, angular_velocity_y); - _mav_put_float(buf, 28, angular_velocity_z); - _mav_put_uint8_t(buf, 32, target_system); - _mav_put_uint8_t(buf, 33, target_component); - _mav_put_uint8_t(buf, 34, gimbal_device_id); - _mav_put_float_array(buf, 4, q, 4); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE, buf, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE_CRC); -#else - mavlink_gimbal_manager_set_attitude_t packet; - packet.flags = flags; - packet.angular_velocity_x = angular_velocity_x; - packet.angular_velocity_y = angular_velocity_y; - packet.angular_velocity_z = angular_velocity_z; - packet.target_system = target_system; - packet.target_component = target_component; - packet.gimbal_device_id = gimbal_device_id; - mav_array_memcpy(packet.q, q, sizeof(float)*4); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE, (const char *)&packet, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE_CRC); -#endif -} - -/** - * @brief Send a gimbal_manager_set_attitude message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_gimbal_manager_set_attitude_send_struct(mavlink_channel_t chan, const mavlink_gimbal_manager_set_attitude_t* gimbal_manager_set_attitude) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_gimbal_manager_set_attitude_send(chan, gimbal_manager_set_attitude->target_system, gimbal_manager_set_attitude->target_component, gimbal_manager_set_attitude->flags, gimbal_manager_set_attitude->gimbal_device_id, gimbal_manager_set_attitude->q, gimbal_manager_set_attitude->angular_velocity_x, gimbal_manager_set_attitude->angular_velocity_y, gimbal_manager_set_attitude->angular_velocity_z); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE, (const char *)gimbal_manager_set_attitude, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE_CRC); -#endif -} - -#if MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_gimbal_manager_set_attitude_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint32_t flags, uint8_t gimbal_device_id, const float *q, float angular_velocity_x, float angular_velocity_y, float angular_velocity_z) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, flags); - _mav_put_float(buf, 20, angular_velocity_x); - _mav_put_float(buf, 24, angular_velocity_y); - _mav_put_float(buf, 28, angular_velocity_z); - _mav_put_uint8_t(buf, 32, target_system); - _mav_put_uint8_t(buf, 33, target_component); - _mav_put_uint8_t(buf, 34, gimbal_device_id); - _mav_put_float_array(buf, 4, q, 4); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE, buf, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE_CRC); -#else - mavlink_gimbal_manager_set_attitude_t *packet = (mavlink_gimbal_manager_set_attitude_t *)msgbuf; - packet->flags = flags; - packet->angular_velocity_x = angular_velocity_x; - packet->angular_velocity_y = angular_velocity_y; - packet->angular_velocity_z = angular_velocity_z; - packet->target_system = target_system; - packet->target_component = target_component; - packet->gimbal_device_id = gimbal_device_id; - mav_array_memcpy(packet->q, q, sizeof(float)*4); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE, (const char *)packet, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE_CRC); -#endif -} -#endif - -#endif - -// MESSAGE GIMBAL_MANAGER_SET_ATTITUDE UNPACKING - - -/** - * @brief Get field target_system from gimbal_manager_set_attitude message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_gimbal_manager_set_attitude_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 32); -} - -/** - * @brief Get field target_component from gimbal_manager_set_attitude message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_gimbal_manager_set_attitude_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 33); -} - -/** - * @brief Get field flags from gimbal_manager_set_attitude message - * - * @return High level gimbal manager flags to use. - */ -static inline uint32_t mavlink_msg_gimbal_manager_set_attitude_get_flags(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field gimbal_device_id from gimbal_manager_set_attitude message - * - * @return Component ID of gimbal device to address (or 1-6 for non-MAVLink gimbal), 0 for all gimbal device components. Send command multiple times for more than one gimbal (but not all gimbals). - */ -static inline uint8_t mavlink_msg_gimbal_manager_set_attitude_get_gimbal_device_id(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 34); -} - -/** - * @brief Get field q from gimbal_manager_set_attitude message - * - * @return Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation, the frame is depends on whether the flag GIMBAL_MANAGER_FLAGS_YAW_LOCK is set) - */ -static inline uint16_t mavlink_msg_gimbal_manager_set_attitude_get_q(const mavlink_message_t* msg, float *q) -{ - return _MAV_RETURN_float_array(msg, q, 4, 4); -} - -/** - * @brief Get field angular_velocity_x from gimbal_manager_set_attitude message - * - * @return [rad/s] X component of angular velocity, positive is rolling to the right, NaN to be ignored. - */ -static inline float mavlink_msg_gimbal_manager_set_attitude_get_angular_velocity_x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Get field angular_velocity_y from gimbal_manager_set_attitude message - * - * @return [rad/s] Y component of angular velocity, positive is pitching up, NaN to be ignored. - */ -static inline float mavlink_msg_gimbal_manager_set_attitude_get_angular_velocity_y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Get field angular_velocity_z from gimbal_manager_set_attitude message - * - * @return [rad/s] Z component of angular velocity, positive is yawing to the right, NaN to be ignored. - */ -static inline float mavlink_msg_gimbal_manager_set_attitude_get_angular_velocity_z(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 28); -} - -/** - * @brief Decode a gimbal_manager_set_attitude message into a struct - * - * @param msg The message to decode - * @param gimbal_manager_set_attitude C-struct to decode the message contents into - */ -static inline void mavlink_msg_gimbal_manager_set_attitude_decode(const mavlink_message_t* msg, mavlink_gimbal_manager_set_attitude_t* gimbal_manager_set_attitude) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - gimbal_manager_set_attitude->flags = mavlink_msg_gimbal_manager_set_attitude_get_flags(msg); - mavlink_msg_gimbal_manager_set_attitude_get_q(msg, gimbal_manager_set_attitude->q); - gimbal_manager_set_attitude->angular_velocity_x = mavlink_msg_gimbal_manager_set_attitude_get_angular_velocity_x(msg); - gimbal_manager_set_attitude->angular_velocity_y = mavlink_msg_gimbal_manager_set_attitude_get_angular_velocity_y(msg); - gimbal_manager_set_attitude->angular_velocity_z = mavlink_msg_gimbal_manager_set_attitude_get_angular_velocity_z(msg); - gimbal_manager_set_attitude->target_system = mavlink_msg_gimbal_manager_set_attitude_get_target_system(msg); - gimbal_manager_set_attitude->target_component = mavlink_msg_gimbal_manager_set_attitude_get_target_component(msg); - gimbal_manager_set_attitude->gimbal_device_id = mavlink_msg_gimbal_manager_set_attitude_get_gimbal_device_id(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE_LEN? msg->len : MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE_LEN; - memset(gimbal_manager_set_attitude, 0, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE_LEN); - memcpy(gimbal_manager_set_attitude, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_gimbal_manager_set_manual_control.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_gimbal_manager_set_manual_control.h deleted file mode 100644 index bf4ac348..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_gimbal_manager_set_manual_control.h +++ /dev/null @@ -1,388 +0,0 @@ -#pragma once -// MESSAGE GIMBAL_MANAGER_SET_MANUAL_CONTROL PACKING - -#define MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_MANUAL_CONTROL 288 - - -typedef struct __mavlink_gimbal_manager_set_manual_control_t { - uint32_t flags; /*< High level gimbal manager flags.*/ - float pitch; /*< Pitch angle unitless (-1..1, positive: up, negative: down, NaN to be ignored).*/ - float yaw; /*< Yaw angle unitless (-1..1, positive: to the right, negative: to the left, NaN to be ignored).*/ - float pitch_rate; /*< Pitch angular rate unitless (-1..1, positive: up, negative: down, NaN to be ignored).*/ - float yaw_rate; /*< Yaw angular rate unitless (-1..1, positive: to the right, negative: to the left, NaN to be ignored).*/ - uint8_t target_system; /*< System ID*/ - uint8_t target_component; /*< Component ID*/ - uint8_t gimbal_device_id; /*< Component ID of gimbal device to address (or 1-6 for non-MAVLink gimbal), 0 for all gimbal device components. Send command multiple times for more than one gimbal (but not all gimbals).*/ -} mavlink_gimbal_manager_set_manual_control_t; - -#define MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_MANUAL_CONTROL_LEN 23 -#define MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_MANUAL_CONTROL_MIN_LEN 23 -#define MAVLINK_MSG_ID_288_LEN 23 -#define MAVLINK_MSG_ID_288_MIN_LEN 23 - -#define MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_MANUAL_CONTROL_CRC 20 -#define MAVLINK_MSG_ID_288_CRC 20 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_GIMBAL_MANAGER_SET_MANUAL_CONTROL { \ - 288, \ - "GIMBAL_MANAGER_SET_MANUAL_CONTROL", \ - 8, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_gimbal_manager_set_manual_control_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 21, offsetof(mavlink_gimbal_manager_set_manual_control_t, target_component) }, \ - { "flags", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_gimbal_manager_set_manual_control_t, flags) }, \ - { "gimbal_device_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 22, offsetof(mavlink_gimbal_manager_set_manual_control_t, gimbal_device_id) }, \ - { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_gimbal_manager_set_manual_control_t, pitch) }, \ - { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_gimbal_manager_set_manual_control_t, yaw) }, \ - { "pitch_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_gimbal_manager_set_manual_control_t, pitch_rate) }, \ - { "yaw_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_gimbal_manager_set_manual_control_t, yaw_rate) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_GIMBAL_MANAGER_SET_MANUAL_CONTROL { \ - "GIMBAL_MANAGER_SET_MANUAL_CONTROL", \ - 8, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_gimbal_manager_set_manual_control_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 21, offsetof(mavlink_gimbal_manager_set_manual_control_t, target_component) }, \ - { "flags", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_gimbal_manager_set_manual_control_t, flags) }, \ - { "gimbal_device_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 22, offsetof(mavlink_gimbal_manager_set_manual_control_t, gimbal_device_id) }, \ - { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_gimbal_manager_set_manual_control_t, pitch) }, \ - { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_gimbal_manager_set_manual_control_t, yaw) }, \ - { "pitch_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_gimbal_manager_set_manual_control_t, pitch_rate) }, \ - { "yaw_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_gimbal_manager_set_manual_control_t, yaw_rate) }, \ - } \ -} -#endif - -/** - * @brief Pack a gimbal_manager_set_manual_control message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID - * @param target_component Component ID - * @param flags High level gimbal manager flags. - * @param gimbal_device_id Component ID of gimbal device to address (or 1-6 for non-MAVLink gimbal), 0 for all gimbal device components. Send command multiple times for more than one gimbal (but not all gimbals). - * @param pitch Pitch angle unitless (-1..1, positive: up, negative: down, NaN to be ignored). - * @param yaw Yaw angle unitless (-1..1, positive: to the right, negative: to the left, NaN to be ignored). - * @param pitch_rate Pitch angular rate unitless (-1..1, positive: up, negative: down, NaN to be ignored). - * @param yaw_rate Yaw angular rate unitless (-1..1, positive: to the right, negative: to the left, NaN to be ignored). - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_gimbal_manager_set_manual_control_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component, uint32_t flags, uint8_t gimbal_device_id, float pitch, float yaw, float pitch_rate, float yaw_rate) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_MANUAL_CONTROL_LEN]; - _mav_put_uint32_t(buf, 0, flags); - _mav_put_float(buf, 4, pitch); - _mav_put_float(buf, 8, yaw); - _mav_put_float(buf, 12, pitch_rate); - _mav_put_float(buf, 16, yaw_rate); - _mav_put_uint8_t(buf, 20, target_system); - _mav_put_uint8_t(buf, 21, target_component); - _mav_put_uint8_t(buf, 22, gimbal_device_id); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_MANUAL_CONTROL_LEN); -#else - mavlink_gimbal_manager_set_manual_control_t packet; - packet.flags = flags; - packet.pitch = pitch; - packet.yaw = yaw; - packet.pitch_rate = pitch_rate; - packet.yaw_rate = yaw_rate; - packet.target_system = target_system; - packet.target_component = target_component; - packet.gimbal_device_id = gimbal_device_id; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_MANUAL_CONTROL_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_MANUAL_CONTROL; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_MANUAL_CONTROL_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_MANUAL_CONTROL_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_MANUAL_CONTROL_CRC); -} - -/** - * @brief Pack a gimbal_manager_set_manual_control message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @param flags High level gimbal manager flags. - * @param gimbal_device_id Component ID of gimbal device to address (or 1-6 for non-MAVLink gimbal), 0 for all gimbal device components. Send command multiple times for more than one gimbal (but not all gimbals). - * @param pitch Pitch angle unitless (-1..1, positive: up, negative: down, NaN to be ignored). - * @param yaw Yaw angle unitless (-1..1, positive: to the right, negative: to the left, NaN to be ignored). - * @param pitch_rate Pitch angular rate unitless (-1..1, positive: up, negative: down, NaN to be ignored). - * @param yaw_rate Yaw angular rate unitless (-1..1, positive: to the right, negative: to the left, NaN to be ignored). - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_gimbal_manager_set_manual_control_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component,uint32_t flags,uint8_t gimbal_device_id,float pitch,float yaw,float pitch_rate,float yaw_rate) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_MANUAL_CONTROL_LEN]; - _mav_put_uint32_t(buf, 0, flags); - _mav_put_float(buf, 4, pitch); - _mav_put_float(buf, 8, yaw); - _mav_put_float(buf, 12, pitch_rate); - _mav_put_float(buf, 16, yaw_rate); - _mav_put_uint8_t(buf, 20, target_system); - _mav_put_uint8_t(buf, 21, target_component); - _mav_put_uint8_t(buf, 22, gimbal_device_id); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_MANUAL_CONTROL_LEN); -#else - mavlink_gimbal_manager_set_manual_control_t packet; - packet.flags = flags; - packet.pitch = pitch; - packet.yaw = yaw; - packet.pitch_rate = pitch_rate; - packet.yaw_rate = yaw_rate; - packet.target_system = target_system; - packet.target_component = target_component; - packet.gimbal_device_id = gimbal_device_id; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_MANUAL_CONTROL_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_MANUAL_CONTROL; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_MANUAL_CONTROL_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_MANUAL_CONTROL_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_MANUAL_CONTROL_CRC); -} - -/** - * @brief Encode a gimbal_manager_set_manual_control struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param gimbal_manager_set_manual_control C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_gimbal_manager_set_manual_control_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gimbal_manager_set_manual_control_t* gimbal_manager_set_manual_control) -{ - return mavlink_msg_gimbal_manager_set_manual_control_pack(system_id, component_id, msg, gimbal_manager_set_manual_control->target_system, gimbal_manager_set_manual_control->target_component, gimbal_manager_set_manual_control->flags, gimbal_manager_set_manual_control->gimbal_device_id, gimbal_manager_set_manual_control->pitch, gimbal_manager_set_manual_control->yaw, gimbal_manager_set_manual_control->pitch_rate, gimbal_manager_set_manual_control->yaw_rate); -} - -/** - * @brief Encode a gimbal_manager_set_manual_control struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param gimbal_manager_set_manual_control C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_gimbal_manager_set_manual_control_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_gimbal_manager_set_manual_control_t* gimbal_manager_set_manual_control) -{ - return mavlink_msg_gimbal_manager_set_manual_control_pack_chan(system_id, component_id, chan, msg, gimbal_manager_set_manual_control->target_system, gimbal_manager_set_manual_control->target_component, gimbal_manager_set_manual_control->flags, gimbal_manager_set_manual_control->gimbal_device_id, gimbal_manager_set_manual_control->pitch, gimbal_manager_set_manual_control->yaw, gimbal_manager_set_manual_control->pitch_rate, gimbal_manager_set_manual_control->yaw_rate); -} - -/** - * @brief Send a gimbal_manager_set_manual_control message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param target_component Component ID - * @param flags High level gimbal manager flags. - * @param gimbal_device_id Component ID of gimbal device to address (or 1-6 for non-MAVLink gimbal), 0 for all gimbal device components. Send command multiple times for more than one gimbal (but not all gimbals). - * @param pitch Pitch angle unitless (-1..1, positive: up, negative: down, NaN to be ignored). - * @param yaw Yaw angle unitless (-1..1, positive: to the right, negative: to the left, NaN to be ignored). - * @param pitch_rate Pitch angular rate unitless (-1..1, positive: up, negative: down, NaN to be ignored). - * @param yaw_rate Yaw angular rate unitless (-1..1, positive: to the right, negative: to the left, NaN to be ignored). - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_gimbal_manager_set_manual_control_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint32_t flags, uint8_t gimbal_device_id, float pitch, float yaw, float pitch_rate, float yaw_rate) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_MANUAL_CONTROL_LEN]; - _mav_put_uint32_t(buf, 0, flags); - _mav_put_float(buf, 4, pitch); - _mav_put_float(buf, 8, yaw); - _mav_put_float(buf, 12, pitch_rate); - _mav_put_float(buf, 16, yaw_rate); - _mav_put_uint8_t(buf, 20, target_system); - _mav_put_uint8_t(buf, 21, target_component); - _mav_put_uint8_t(buf, 22, gimbal_device_id); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_MANUAL_CONTROL, buf, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_MANUAL_CONTROL_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_MANUAL_CONTROL_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_MANUAL_CONTROL_CRC); -#else - mavlink_gimbal_manager_set_manual_control_t packet; - packet.flags = flags; - packet.pitch = pitch; - packet.yaw = yaw; - packet.pitch_rate = pitch_rate; - packet.yaw_rate = yaw_rate; - packet.target_system = target_system; - packet.target_component = target_component; - packet.gimbal_device_id = gimbal_device_id; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_MANUAL_CONTROL, (const char *)&packet, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_MANUAL_CONTROL_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_MANUAL_CONTROL_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_MANUAL_CONTROL_CRC); -#endif -} - -/** - * @brief Send a gimbal_manager_set_manual_control message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_gimbal_manager_set_manual_control_send_struct(mavlink_channel_t chan, const mavlink_gimbal_manager_set_manual_control_t* gimbal_manager_set_manual_control) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_gimbal_manager_set_manual_control_send(chan, gimbal_manager_set_manual_control->target_system, gimbal_manager_set_manual_control->target_component, gimbal_manager_set_manual_control->flags, gimbal_manager_set_manual_control->gimbal_device_id, gimbal_manager_set_manual_control->pitch, gimbal_manager_set_manual_control->yaw, gimbal_manager_set_manual_control->pitch_rate, gimbal_manager_set_manual_control->yaw_rate); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_MANUAL_CONTROL, (const char *)gimbal_manager_set_manual_control, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_MANUAL_CONTROL_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_MANUAL_CONTROL_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_MANUAL_CONTROL_CRC); -#endif -} - -#if MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_MANUAL_CONTROL_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_gimbal_manager_set_manual_control_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint32_t flags, uint8_t gimbal_device_id, float pitch, float yaw, float pitch_rate, float yaw_rate) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, flags); - _mav_put_float(buf, 4, pitch); - _mav_put_float(buf, 8, yaw); - _mav_put_float(buf, 12, pitch_rate); - _mav_put_float(buf, 16, yaw_rate); - _mav_put_uint8_t(buf, 20, target_system); - _mav_put_uint8_t(buf, 21, target_component); - _mav_put_uint8_t(buf, 22, gimbal_device_id); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_MANUAL_CONTROL, buf, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_MANUAL_CONTROL_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_MANUAL_CONTROL_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_MANUAL_CONTROL_CRC); -#else - mavlink_gimbal_manager_set_manual_control_t *packet = (mavlink_gimbal_manager_set_manual_control_t *)msgbuf; - packet->flags = flags; - packet->pitch = pitch; - packet->yaw = yaw; - packet->pitch_rate = pitch_rate; - packet->yaw_rate = yaw_rate; - packet->target_system = target_system; - packet->target_component = target_component; - packet->gimbal_device_id = gimbal_device_id; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_MANUAL_CONTROL, (const char *)packet, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_MANUAL_CONTROL_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_MANUAL_CONTROL_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_MANUAL_CONTROL_CRC); -#endif -} -#endif - -#endif - -// MESSAGE GIMBAL_MANAGER_SET_MANUAL_CONTROL UNPACKING - - -/** - * @brief Get field target_system from gimbal_manager_set_manual_control message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_gimbal_manager_set_manual_control_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 20); -} - -/** - * @brief Get field target_component from gimbal_manager_set_manual_control message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_gimbal_manager_set_manual_control_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 21); -} - -/** - * @brief Get field flags from gimbal_manager_set_manual_control message - * - * @return High level gimbal manager flags. - */ -static inline uint32_t mavlink_msg_gimbal_manager_set_manual_control_get_flags(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field gimbal_device_id from gimbal_manager_set_manual_control message - * - * @return Component ID of gimbal device to address (or 1-6 for non-MAVLink gimbal), 0 for all gimbal device components. Send command multiple times for more than one gimbal (but not all gimbals). - */ -static inline uint8_t mavlink_msg_gimbal_manager_set_manual_control_get_gimbal_device_id(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 22); -} - -/** - * @brief Get field pitch from gimbal_manager_set_manual_control message - * - * @return Pitch angle unitless (-1..1, positive: up, negative: down, NaN to be ignored). - */ -static inline float mavlink_msg_gimbal_manager_set_manual_control_get_pitch(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 4); -} - -/** - * @brief Get field yaw from gimbal_manager_set_manual_control message - * - * @return Yaw angle unitless (-1..1, positive: to the right, negative: to the left, NaN to be ignored). - */ -static inline float mavlink_msg_gimbal_manager_set_manual_control_get_yaw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field pitch_rate from gimbal_manager_set_manual_control message - * - * @return Pitch angular rate unitless (-1..1, positive: up, negative: down, NaN to be ignored). - */ -static inline float mavlink_msg_gimbal_manager_set_manual_control_get_pitch_rate(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field yaw_rate from gimbal_manager_set_manual_control message - * - * @return Yaw angular rate unitless (-1..1, positive: to the right, negative: to the left, NaN to be ignored). - */ -static inline float mavlink_msg_gimbal_manager_set_manual_control_get_yaw_rate(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Decode a gimbal_manager_set_manual_control message into a struct - * - * @param msg The message to decode - * @param gimbal_manager_set_manual_control C-struct to decode the message contents into - */ -static inline void mavlink_msg_gimbal_manager_set_manual_control_decode(const mavlink_message_t* msg, mavlink_gimbal_manager_set_manual_control_t* gimbal_manager_set_manual_control) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - gimbal_manager_set_manual_control->flags = mavlink_msg_gimbal_manager_set_manual_control_get_flags(msg); - gimbal_manager_set_manual_control->pitch = mavlink_msg_gimbal_manager_set_manual_control_get_pitch(msg); - gimbal_manager_set_manual_control->yaw = mavlink_msg_gimbal_manager_set_manual_control_get_yaw(msg); - gimbal_manager_set_manual_control->pitch_rate = mavlink_msg_gimbal_manager_set_manual_control_get_pitch_rate(msg); - gimbal_manager_set_manual_control->yaw_rate = mavlink_msg_gimbal_manager_set_manual_control_get_yaw_rate(msg); - gimbal_manager_set_manual_control->target_system = mavlink_msg_gimbal_manager_set_manual_control_get_target_system(msg); - gimbal_manager_set_manual_control->target_component = mavlink_msg_gimbal_manager_set_manual_control_get_target_component(msg); - gimbal_manager_set_manual_control->gimbal_device_id = mavlink_msg_gimbal_manager_set_manual_control_get_gimbal_device_id(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_MANUAL_CONTROL_LEN? msg->len : MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_MANUAL_CONTROL_LEN; - memset(gimbal_manager_set_manual_control, 0, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_MANUAL_CONTROL_LEN); - memcpy(gimbal_manager_set_manual_control, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_gimbal_manager_set_pitchyaw.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_gimbal_manager_set_pitchyaw.h deleted file mode 100644 index 5972e913..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_gimbal_manager_set_pitchyaw.h +++ /dev/null @@ -1,388 +0,0 @@ -#pragma once -// MESSAGE GIMBAL_MANAGER_SET_PITCHYAW PACKING - -#define MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_PITCHYAW 287 - - -typedef struct __mavlink_gimbal_manager_set_pitchyaw_t { - uint32_t flags; /*< High level gimbal manager flags to use.*/ - float pitch; /*< [rad] Pitch angle (positive: up, negative: down, NaN to be ignored).*/ - float yaw; /*< [rad] Yaw angle (positive: to the right, negative: to the left, NaN to be ignored).*/ - float pitch_rate; /*< [rad/s] Pitch angular rate (positive: up, negative: down, NaN to be ignored).*/ - float yaw_rate; /*< [rad/s] Yaw angular rate (positive: to the right, negative: to the left, NaN to be ignored).*/ - uint8_t target_system; /*< System ID*/ - uint8_t target_component; /*< Component ID*/ - uint8_t gimbal_device_id; /*< Component ID of gimbal device to address (or 1-6 for non-MAVLink gimbal), 0 for all gimbal device components. Send command multiple times for more than one gimbal (but not all gimbals).*/ -} mavlink_gimbal_manager_set_pitchyaw_t; - -#define MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_PITCHYAW_LEN 23 -#define MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_PITCHYAW_MIN_LEN 23 -#define MAVLINK_MSG_ID_287_LEN 23 -#define MAVLINK_MSG_ID_287_MIN_LEN 23 - -#define MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_PITCHYAW_CRC 1 -#define MAVLINK_MSG_ID_287_CRC 1 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_GIMBAL_MANAGER_SET_PITCHYAW { \ - 287, \ - "GIMBAL_MANAGER_SET_PITCHYAW", \ - 8, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_gimbal_manager_set_pitchyaw_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 21, offsetof(mavlink_gimbal_manager_set_pitchyaw_t, target_component) }, \ - { "flags", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_gimbal_manager_set_pitchyaw_t, flags) }, \ - { "gimbal_device_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 22, offsetof(mavlink_gimbal_manager_set_pitchyaw_t, gimbal_device_id) }, \ - { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_gimbal_manager_set_pitchyaw_t, pitch) }, \ - { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_gimbal_manager_set_pitchyaw_t, yaw) }, \ - { "pitch_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_gimbal_manager_set_pitchyaw_t, pitch_rate) }, \ - { "yaw_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_gimbal_manager_set_pitchyaw_t, yaw_rate) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_GIMBAL_MANAGER_SET_PITCHYAW { \ - "GIMBAL_MANAGER_SET_PITCHYAW", \ - 8, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_gimbal_manager_set_pitchyaw_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 21, offsetof(mavlink_gimbal_manager_set_pitchyaw_t, target_component) }, \ - { "flags", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_gimbal_manager_set_pitchyaw_t, flags) }, \ - { "gimbal_device_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 22, offsetof(mavlink_gimbal_manager_set_pitchyaw_t, gimbal_device_id) }, \ - { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_gimbal_manager_set_pitchyaw_t, pitch) }, \ - { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_gimbal_manager_set_pitchyaw_t, yaw) }, \ - { "pitch_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_gimbal_manager_set_pitchyaw_t, pitch_rate) }, \ - { "yaw_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_gimbal_manager_set_pitchyaw_t, yaw_rate) }, \ - } \ -} -#endif - -/** - * @brief Pack a gimbal_manager_set_pitchyaw message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID - * @param target_component Component ID - * @param flags High level gimbal manager flags to use. - * @param gimbal_device_id Component ID of gimbal device to address (or 1-6 for non-MAVLink gimbal), 0 for all gimbal device components. Send command multiple times for more than one gimbal (but not all gimbals). - * @param pitch [rad] Pitch angle (positive: up, negative: down, NaN to be ignored). - * @param yaw [rad] Yaw angle (positive: to the right, negative: to the left, NaN to be ignored). - * @param pitch_rate [rad/s] Pitch angular rate (positive: up, negative: down, NaN to be ignored). - * @param yaw_rate [rad/s] Yaw angular rate (positive: to the right, negative: to the left, NaN to be ignored). - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_gimbal_manager_set_pitchyaw_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component, uint32_t flags, uint8_t gimbal_device_id, float pitch, float yaw, float pitch_rate, float yaw_rate) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_PITCHYAW_LEN]; - _mav_put_uint32_t(buf, 0, flags); - _mav_put_float(buf, 4, pitch); - _mav_put_float(buf, 8, yaw); - _mav_put_float(buf, 12, pitch_rate); - _mav_put_float(buf, 16, yaw_rate); - _mav_put_uint8_t(buf, 20, target_system); - _mav_put_uint8_t(buf, 21, target_component); - _mav_put_uint8_t(buf, 22, gimbal_device_id); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_PITCHYAW_LEN); -#else - mavlink_gimbal_manager_set_pitchyaw_t packet; - packet.flags = flags; - packet.pitch = pitch; - packet.yaw = yaw; - packet.pitch_rate = pitch_rate; - packet.yaw_rate = yaw_rate; - packet.target_system = target_system; - packet.target_component = target_component; - packet.gimbal_device_id = gimbal_device_id; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_PITCHYAW_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_PITCHYAW; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_PITCHYAW_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_PITCHYAW_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_PITCHYAW_CRC); -} - -/** - * @brief Pack a gimbal_manager_set_pitchyaw message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @param flags High level gimbal manager flags to use. - * @param gimbal_device_id Component ID of gimbal device to address (or 1-6 for non-MAVLink gimbal), 0 for all gimbal device components. Send command multiple times for more than one gimbal (but not all gimbals). - * @param pitch [rad] Pitch angle (positive: up, negative: down, NaN to be ignored). - * @param yaw [rad] Yaw angle (positive: to the right, negative: to the left, NaN to be ignored). - * @param pitch_rate [rad/s] Pitch angular rate (positive: up, negative: down, NaN to be ignored). - * @param yaw_rate [rad/s] Yaw angular rate (positive: to the right, negative: to the left, NaN to be ignored). - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_gimbal_manager_set_pitchyaw_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component,uint32_t flags,uint8_t gimbal_device_id,float pitch,float yaw,float pitch_rate,float yaw_rate) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_PITCHYAW_LEN]; - _mav_put_uint32_t(buf, 0, flags); - _mav_put_float(buf, 4, pitch); - _mav_put_float(buf, 8, yaw); - _mav_put_float(buf, 12, pitch_rate); - _mav_put_float(buf, 16, yaw_rate); - _mav_put_uint8_t(buf, 20, target_system); - _mav_put_uint8_t(buf, 21, target_component); - _mav_put_uint8_t(buf, 22, gimbal_device_id); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_PITCHYAW_LEN); -#else - mavlink_gimbal_manager_set_pitchyaw_t packet; - packet.flags = flags; - packet.pitch = pitch; - packet.yaw = yaw; - packet.pitch_rate = pitch_rate; - packet.yaw_rate = yaw_rate; - packet.target_system = target_system; - packet.target_component = target_component; - packet.gimbal_device_id = gimbal_device_id; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_PITCHYAW_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_PITCHYAW; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_PITCHYAW_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_PITCHYAW_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_PITCHYAW_CRC); -} - -/** - * @brief Encode a gimbal_manager_set_pitchyaw struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param gimbal_manager_set_pitchyaw C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_gimbal_manager_set_pitchyaw_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gimbal_manager_set_pitchyaw_t* gimbal_manager_set_pitchyaw) -{ - return mavlink_msg_gimbal_manager_set_pitchyaw_pack(system_id, component_id, msg, gimbal_manager_set_pitchyaw->target_system, gimbal_manager_set_pitchyaw->target_component, gimbal_manager_set_pitchyaw->flags, gimbal_manager_set_pitchyaw->gimbal_device_id, gimbal_manager_set_pitchyaw->pitch, gimbal_manager_set_pitchyaw->yaw, gimbal_manager_set_pitchyaw->pitch_rate, gimbal_manager_set_pitchyaw->yaw_rate); -} - -/** - * @brief Encode a gimbal_manager_set_pitchyaw struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param gimbal_manager_set_pitchyaw C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_gimbal_manager_set_pitchyaw_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_gimbal_manager_set_pitchyaw_t* gimbal_manager_set_pitchyaw) -{ - return mavlink_msg_gimbal_manager_set_pitchyaw_pack_chan(system_id, component_id, chan, msg, gimbal_manager_set_pitchyaw->target_system, gimbal_manager_set_pitchyaw->target_component, gimbal_manager_set_pitchyaw->flags, gimbal_manager_set_pitchyaw->gimbal_device_id, gimbal_manager_set_pitchyaw->pitch, gimbal_manager_set_pitchyaw->yaw, gimbal_manager_set_pitchyaw->pitch_rate, gimbal_manager_set_pitchyaw->yaw_rate); -} - -/** - * @brief Send a gimbal_manager_set_pitchyaw message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param target_component Component ID - * @param flags High level gimbal manager flags to use. - * @param gimbal_device_id Component ID of gimbal device to address (or 1-6 for non-MAVLink gimbal), 0 for all gimbal device components. Send command multiple times for more than one gimbal (but not all gimbals). - * @param pitch [rad] Pitch angle (positive: up, negative: down, NaN to be ignored). - * @param yaw [rad] Yaw angle (positive: to the right, negative: to the left, NaN to be ignored). - * @param pitch_rate [rad/s] Pitch angular rate (positive: up, negative: down, NaN to be ignored). - * @param yaw_rate [rad/s] Yaw angular rate (positive: to the right, negative: to the left, NaN to be ignored). - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_gimbal_manager_set_pitchyaw_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint32_t flags, uint8_t gimbal_device_id, float pitch, float yaw, float pitch_rate, float yaw_rate) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_PITCHYAW_LEN]; - _mav_put_uint32_t(buf, 0, flags); - _mav_put_float(buf, 4, pitch); - _mav_put_float(buf, 8, yaw); - _mav_put_float(buf, 12, pitch_rate); - _mav_put_float(buf, 16, yaw_rate); - _mav_put_uint8_t(buf, 20, target_system); - _mav_put_uint8_t(buf, 21, target_component); - _mav_put_uint8_t(buf, 22, gimbal_device_id); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_PITCHYAW, buf, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_PITCHYAW_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_PITCHYAW_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_PITCHYAW_CRC); -#else - mavlink_gimbal_manager_set_pitchyaw_t packet; - packet.flags = flags; - packet.pitch = pitch; - packet.yaw = yaw; - packet.pitch_rate = pitch_rate; - packet.yaw_rate = yaw_rate; - packet.target_system = target_system; - packet.target_component = target_component; - packet.gimbal_device_id = gimbal_device_id; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_PITCHYAW, (const char *)&packet, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_PITCHYAW_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_PITCHYAW_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_PITCHYAW_CRC); -#endif -} - -/** - * @brief Send a gimbal_manager_set_pitchyaw message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_gimbal_manager_set_pitchyaw_send_struct(mavlink_channel_t chan, const mavlink_gimbal_manager_set_pitchyaw_t* gimbal_manager_set_pitchyaw) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_gimbal_manager_set_pitchyaw_send(chan, gimbal_manager_set_pitchyaw->target_system, gimbal_manager_set_pitchyaw->target_component, gimbal_manager_set_pitchyaw->flags, gimbal_manager_set_pitchyaw->gimbal_device_id, gimbal_manager_set_pitchyaw->pitch, gimbal_manager_set_pitchyaw->yaw, gimbal_manager_set_pitchyaw->pitch_rate, gimbal_manager_set_pitchyaw->yaw_rate); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_PITCHYAW, (const char *)gimbal_manager_set_pitchyaw, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_PITCHYAW_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_PITCHYAW_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_PITCHYAW_CRC); -#endif -} - -#if MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_PITCHYAW_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_gimbal_manager_set_pitchyaw_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint32_t flags, uint8_t gimbal_device_id, float pitch, float yaw, float pitch_rate, float yaw_rate) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, flags); - _mav_put_float(buf, 4, pitch); - _mav_put_float(buf, 8, yaw); - _mav_put_float(buf, 12, pitch_rate); - _mav_put_float(buf, 16, yaw_rate); - _mav_put_uint8_t(buf, 20, target_system); - _mav_put_uint8_t(buf, 21, target_component); - _mav_put_uint8_t(buf, 22, gimbal_device_id); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_PITCHYAW, buf, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_PITCHYAW_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_PITCHYAW_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_PITCHYAW_CRC); -#else - mavlink_gimbal_manager_set_pitchyaw_t *packet = (mavlink_gimbal_manager_set_pitchyaw_t *)msgbuf; - packet->flags = flags; - packet->pitch = pitch; - packet->yaw = yaw; - packet->pitch_rate = pitch_rate; - packet->yaw_rate = yaw_rate; - packet->target_system = target_system; - packet->target_component = target_component; - packet->gimbal_device_id = gimbal_device_id; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_PITCHYAW, (const char *)packet, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_PITCHYAW_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_PITCHYAW_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_PITCHYAW_CRC); -#endif -} -#endif - -#endif - -// MESSAGE GIMBAL_MANAGER_SET_PITCHYAW UNPACKING - - -/** - * @brief Get field target_system from gimbal_manager_set_pitchyaw message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_gimbal_manager_set_pitchyaw_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 20); -} - -/** - * @brief Get field target_component from gimbal_manager_set_pitchyaw message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_gimbal_manager_set_pitchyaw_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 21); -} - -/** - * @brief Get field flags from gimbal_manager_set_pitchyaw message - * - * @return High level gimbal manager flags to use. - */ -static inline uint32_t mavlink_msg_gimbal_manager_set_pitchyaw_get_flags(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field gimbal_device_id from gimbal_manager_set_pitchyaw message - * - * @return Component ID of gimbal device to address (or 1-6 for non-MAVLink gimbal), 0 for all gimbal device components. Send command multiple times for more than one gimbal (but not all gimbals). - */ -static inline uint8_t mavlink_msg_gimbal_manager_set_pitchyaw_get_gimbal_device_id(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 22); -} - -/** - * @brief Get field pitch from gimbal_manager_set_pitchyaw message - * - * @return [rad] Pitch angle (positive: up, negative: down, NaN to be ignored). - */ -static inline float mavlink_msg_gimbal_manager_set_pitchyaw_get_pitch(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 4); -} - -/** - * @brief Get field yaw from gimbal_manager_set_pitchyaw message - * - * @return [rad] Yaw angle (positive: to the right, negative: to the left, NaN to be ignored). - */ -static inline float mavlink_msg_gimbal_manager_set_pitchyaw_get_yaw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field pitch_rate from gimbal_manager_set_pitchyaw message - * - * @return [rad/s] Pitch angular rate (positive: up, negative: down, NaN to be ignored). - */ -static inline float mavlink_msg_gimbal_manager_set_pitchyaw_get_pitch_rate(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field yaw_rate from gimbal_manager_set_pitchyaw message - * - * @return [rad/s] Yaw angular rate (positive: to the right, negative: to the left, NaN to be ignored). - */ -static inline float mavlink_msg_gimbal_manager_set_pitchyaw_get_yaw_rate(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Decode a gimbal_manager_set_pitchyaw message into a struct - * - * @param msg The message to decode - * @param gimbal_manager_set_pitchyaw C-struct to decode the message contents into - */ -static inline void mavlink_msg_gimbal_manager_set_pitchyaw_decode(const mavlink_message_t* msg, mavlink_gimbal_manager_set_pitchyaw_t* gimbal_manager_set_pitchyaw) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - gimbal_manager_set_pitchyaw->flags = mavlink_msg_gimbal_manager_set_pitchyaw_get_flags(msg); - gimbal_manager_set_pitchyaw->pitch = mavlink_msg_gimbal_manager_set_pitchyaw_get_pitch(msg); - gimbal_manager_set_pitchyaw->yaw = mavlink_msg_gimbal_manager_set_pitchyaw_get_yaw(msg); - gimbal_manager_set_pitchyaw->pitch_rate = mavlink_msg_gimbal_manager_set_pitchyaw_get_pitch_rate(msg); - gimbal_manager_set_pitchyaw->yaw_rate = mavlink_msg_gimbal_manager_set_pitchyaw_get_yaw_rate(msg); - gimbal_manager_set_pitchyaw->target_system = mavlink_msg_gimbal_manager_set_pitchyaw_get_target_system(msg); - gimbal_manager_set_pitchyaw->target_component = mavlink_msg_gimbal_manager_set_pitchyaw_get_target_component(msg); - gimbal_manager_set_pitchyaw->gimbal_device_id = mavlink_msg_gimbal_manager_set_pitchyaw_get_gimbal_device_id(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_PITCHYAW_LEN? msg->len : MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_PITCHYAW_LEN; - memset(gimbal_manager_set_pitchyaw, 0, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_PITCHYAW_LEN); - memcpy(gimbal_manager_set_pitchyaw, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_gimbal_manager_status.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_gimbal_manager_status.h deleted file mode 100644 index 484d2ab5..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_gimbal_manager_status.h +++ /dev/null @@ -1,363 +0,0 @@ -#pragma once -// MESSAGE GIMBAL_MANAGER_STATUS PACKING - -#define MAVLINK_MSG_ID_GIMBAL_MANAGER_STATUS 281 - - -typedef struct __mavlink_gimbal_manager_status_t { - uint32_t time_boot_ms; /*< [ms] Timestamp (time since system boot).*/ - uint32_t flags; /*< High level gimbal manager flags currently applied.*/ - uint8_t gimbal_device_id; /*< Gimbal device ID that this gimbal manager is responsible for. Component ID of gimbal device (or 1-6 for non-MAVLink gimbal).*/ - uint8_t primary_control_sysid; /*< System ID of MAVLink component with primary control, 0 for none.*/ - uint8_t primary_control_compid; /*< Component ID of MAVLink component with primary control, 0 for none.*/ - uint8_t secondary_control_sysid; /*< System ID of MAVLink component with secondary control, 0 for none.*/ - uint8_t secondary_control_compid; /*< Component ID of MAVLink component with secondary control, 0 for none.*/ -} mavlink_gimbal_manager_status_t; - -#define MAVLINK_MSG_ID_GIMBAL_MANAGER_STATUS_LEN 13 -#define MAVLINK_MSG_ID_GIMBAL_MANAGER_STATUS_MIN_LEN 13 -#define MAVLINK_MSG_ID_281_LEN 13 -#define MAVLINK_MSG_ID_281_MIN_LEN 13 - -#define MAVLINK_MSG_ID_GIMBAL_MANAGER_STATUS_CRC 48 -#define MAVLINK_MSG_ID_281_CRC 48 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_GIMBAL_MANAGER_STATUS { \ - 281, \ - "GIMBAL_MANAGER_STATUS", \ - 7, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_gimbal_manager_status_t, time_boot_ms) }, \ - { "flags", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_gimbal_manager_status_t, flags) }, \ - { "gimbal_device_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_gimbal_manager_status_t, gimbal_device_id) }, \ - { "primary_control_sysid", NULL, MAVLINK_TYPE_UINT8_T, 0, 9, offsetof(mavlink_gimbal_manager_status_t, primary_control_sysid) }, \ - { "primary_control_compid", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_gimbal_manager_status_t, primary_control_compid) }, \ - { "secondary_control_sysid", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_gimbal_manager_status_t, secondary_control_sysid) }, \ - { "secondary_control_compid", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_gimbal_manager_status_t, secondary_control_compid) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_GIMBAL_MANAGER_STATUS { \ - "GIMBAL_MANAGER_STATUS", \ - 7, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_gimbal_manager_status_t, time_boot_ms) }, \ - { "flags", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_gimbal_manager_status_t, flags) }, \ - { "gimbal_device_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_gimbal_manager_status_t, gimbal_device_id) }, \ - { "primary_control_sysid", NULL, MAVLINK_TYPE_UINT8_T, 0, 9, offsetof(mavlink_gimbal_manager_status_t, primary_control_sysid) }, \ - { "primary_control_compid", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_gimbal_manager_status_t, primary_control_compid) }, \ - { "secondary_control_sysid", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_gimbal_manager_status_t, secondary_control_sysid) }, \ - { "secondary_control_compid", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_gimbal_manager_status_t, secondary_control_compid) }, \ - } \ -} -#endif - -/** - * @brief Pack a gimbal_manager_status message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param time_boot_ms [ms] Timestamp (time since system boot). - * @param flags High level gimbal manager flags currently applied. - * @param gimbal_device_id Gimbal device ID that this gimbal manager is responsible for. Component ID of gimbal device (or 1-6 for non-MAVLink gimbal). - * @param primary_control_sysid System ID of MAVLink component with primary control, 0 for none. - * @param primary_control_compid Component ID of MAVLink component with primary control, 0 for none. - * @param secondary_control_sysid System ID of MAVLink component with secondary control, 0 for none. - * @param secondary_control_compid Component ID of MAVLink component with secondary control, 0 for none. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_gimbal_manager_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint32_t time_boot_ms, uint32_t flags, uint8_t gimbal_device_id, uint8_t primary_control_sysid, uint8_t primary_control_compid, uint8_t secondary_control_sysid, uint8_t secondary_control_compid) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_GIMBAL_MANAGER_STATUS_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_uint32_t(buf, 4, flags); - _mav_put_uint8_t(buf, 8, gimbal_device_id); - _mav_put_uint8_t(buf, 9, primary_control_sysid); - _mav_put_uint8_t(buf, 10, primary_control_compid); - _mav_put_uint8_t(buf, 11, secondary_control_sysid); - _mav_put_uint8_t(buf, 12, secondary_control_compid); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GIMBAL_MANAGER_STATUS_LEN); -#else - mavlink_gimbal_manager_status_t packet; - packet.time_boot_ms = time_boot_ms; - packet.flags = flags; - packet.gimbal_device_id = gimbal_device_id; - packet.primary_control_sysid = primary_control_sysid; - packet.primary_control_compid = primary_control_compid; - packet.secondary_control_sysid = secondary_control_sysid; - packet.secondary_control_compid = secondary_control_compid; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GIMBAL_MANAGER_STATUS_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_GIMBAL_MANAGER_STATUS; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GIMBAL_MANAGER_STATUS_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_STATUS_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_STATUS_CRC); -} - -/** - * @brief Pack a gimbal_manager_status message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_boot_ms [ms] Timestamp (time since system boot). - * @param flags High level gimbal manager flags currently applied. - * @param gimbal_device_id Gimbal device ID that this gimbal manager is responsible for. Component ID of gimbal device (or 1-6 for non-MAVLink gimbal). - * @param primary_control_sysid System ID of MAVLink component with primary control, 0 for none. - * @param primary_control_compid Component ID of MAVLink component with primary control, 0 for none. - * @param secondary_control_sysid System ID of MAVLink component with secondary control, 0 for none. - * @param secondary_control_compid Component ID of MAVLink component with secondary control, 0 for none. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_gimbal_manager_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint32_t time_boot_ms,uint32_t flags,uint8_t gimbal_device_id,uint8_t primary_control_sysid,uint8_t primary_control_compid,uint8_t secondary_control_sysid,uint8_t secondary_control_compid) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_GIMBAL_MANAGER_STATUS_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_uint32_t(buf, 4, flags); - _mav_put_uint8_t(buf, 8, gimbal_device_id); - _mav_put_uint8_t(buf, 9, primary_control_sysid); - _mav_put_uint8_t(buf, 10, primary_control_compid); - _mav_put_uint8_t(buf, 11, secondary_control_sysid); - _mav_put_uint8_t(buf, 12, secondary_control_compid); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GIMBAL_MANAGER_STATUS_LEN); -#else - mavlink_gimbal_manager_status_t packet; - packet.time_boot_ms = time_boot_ms; - packet.flags = flags; - packet.gimbal_device_id = gimbal_device_id; - packet.primary_control_sysid = primary_control_sysid; - packet.primary_control_compid = primary_control_compid; - packet.secondary_control_sysid = secondary_control_sysid; - packet.secondary_control_compid = secondary_control_compid; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GIMBAL_MANAGER_STATUS_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_GIMBAL_MANAGER_STATUS; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GIMBAL_MANAGER_STATUS_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_STATUS_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_STATUS_CRC); -} - -/** - * @brief Encode a gimbal_manager_status struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param gimbal_manager_status C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_gimbal_manager_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gimbal_manager_status_t* gimbal_manager_status) -{ - return mavlink_msg_gimbal_manager_status_pack(system_id, component_id, msg, gimbal_manager_status->time_boot_ms, gimbal_manager_status->flags, gimbal_manager_status->gimbal_device_id, gimbal_manager_status->primary_control_sysid, gimbal_manager_status->primary_control_compid, gimbal_manager_status->secondary_control_sysid, gimbal_manager_status->secondary_control_compid); -} - -/** - * @brief Encode a gimbal_manager_status struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param gimbal_manager_status C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_gimbal_manager_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_gimbal_manager_status_t* gimbal_manager_status) -{ - return mavlink_msg_gimbal_manager_status_pack_chan(system_id, component_id, chan, msg, gimbal_manager_status->time_boot_ms, gimbal_manager_status->flags, gimbal_manager_status->gimbal_device_id, gimbal_manager_status->primary_control_sysid, gimbal_manager_status->primary_control_compid, gimbal_manager_status->secondary_control_sysid, gimbal_manager_status->secondary_control_compid); -} - -/** - * @brief Send a gimbal_manager_status message - * @param chan MAVLink channel to send the message - * - * @param time_boot_ms [ms] Timestamp (time since system boot). - * @param flags High level gimbal manager flags currently applied. - * @param gimbal_device_id Gimbal device ID that this gimbal manager is responsible for. Component ID of gimbal device (or 1-6 for non-MAVLink gimbal). - * @param primary_control_sysid System ID of MAVLink component with primary control, 0 for none. - * @param primary_control_compid Component ID of MAVLink component with primary control, 0 for none. - * @param secondary_control_sysid System ID of MAVLink component with secondary control, 0 for none. - * @param secondary_control_compid Component ID of MAVLink component with secondary control, 0 for none. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_gimbal_manager_status_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint32_t flags, uint8_t gimbal_device_id, uint8_t primary_control_sysid, uint8_t primary_control_compid, uint8_t secondary_control_sysid, uint8_t secondary_control_compid) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_GIMBAL_MANAGER_STATUS_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_uint32_t(buf, 4, flags); - _mav_put_uint8_t(buf, 8, gimbal_device_id); - _mav_put_uint8_t(buf, 9, primary_control_sysid); - _mav_put_uint8_t(buf, 10, primary_control_compid); - _mav_put_uint8_t(buf, 11, secondary_control_sysid); - _mav_put_uint8_t(buf, 12, secondary_control_compid); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_MANAGER_STATUS, buf, MAVLINK_MSG_ID_GIMBAL_MANAGER_STATUS_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_STATUS_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_STATUS_CRC); -#else - mavlink_gimbal_manager_status_t packet; - packet.time_boot_ms = time_boot_ms; - packet.flags = flags; - packet.gimbal_device_id = gimbal_device_id; - packet.primary_control_sysid = primary_control_sysid; - packet.primary_control_compid = primary_control_compid; - packet.secondary_control_sysid = secondary_control_sysid; - packet.secondary_control_compid = secondary_control_compid; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_MANAGER_STATUS, (const char *)&packet, MAVLINK_MSG_ID_GIMBAL_MANAGER_STATUS_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_STATUS_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_STATUS_CRC); -#endif -} - -/** - * @brief Send a gimbal_manager_status message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_gimbal_manager_status_send_struct(mavlink_channel_t chan, const mavlink_gimbal_manager_status_t* gimbal_manager_status) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_gimbal_manager_status_send(chan, gimbal_manager_status->time_boot_ms, gimbal_manager_status->flags, gimbal_manager_status->gimbal_device_id, gimbal_manager_status->primary_control_sysid, gimbal_manager_status->primary_control_compid, gimbal_manager_status->secondary_control_sysid, gimbal_manager_status->secondary_control_compid); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_MANAGER_STATUS, (const char *)gimbal_manager_status, MAVLINK_MSG_ID_GIMBAL_MANAGER_STATUS_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_STATUS_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_STATUS_CRC); -#endif -} - -#if MAVLINK_MSG_ID_GIMBAL_MANAGER_STATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_gimbal_manager_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint32_t flags, uint8_t gimbal_device_id, uint8_t primary_control_sysid, uint8_t primary_control_compid, uint8_t secondary_control_sysid, uint8_t secondary_control_compid) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_uint32_t(buf, 4, flags); - _mav_put_uint8_t(buf, 8, gimbal_device_id); - _mav_put_uint8_t(buf, 9, primary_control_sysid); - _mav_put_uint8_t(buf, 10, primary_control_compid); - _mav_put_uint8_t(buf, 11, secondary_control_sysid); - _mav_put_uint8_t(buf, 12, secondary_control_compid); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_MANAGER_STATUS, buf, MAVLINK_MSG_ID_GIMBAL_MANAGER_STATUS_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_STATUS_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_STATUS_CRC); -#else - mavlink_gimbal_manager_status_t *packet = (mavlink_gimbal_manager_status_t *)msgbuf; - packet->time_boot_ms = time_boot_ms; - packet->flags = flags; - packet->gimbal_device_id = gimbal_device_id; - packet->primary_control_sysid = primary_control_sysid; - packet->primary_control_compid = primary_control_compid; - packet->secondary_control_sysid = secondary_control_sysid; - packet->secondary_control_compid = secondary_control_compid; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_MANAGER_STATUS, (const char *)packet, MAVLINK_MSG_ID_GIMBAL_MANAGER_STATUS_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_STATUS_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_STATUS_CRC); -#endif -} -#endif - -#endif - -// MESSAGE GIMBAL_MANAGER_STATUS UNPACKING - - -/** - * @brief Get field time_boot_ms from gimbal_manager_status message - * - * @return [ms] Timestamp (time since system boot). - */ -static inline uint32_t mavlink_msg_gimbal_manager_status_get_time_boot_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field flags from gimbal_manager_status message - * - * @return High level gimbal manager flags currently applied. - */ -static inline uint32_t mavlink_msg_gimbal_manager_status_get_flags(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 4); -} - -/** - * @brief Get field gimbal_device_id from gimbal_manager_status message - * - * @return Gimbal device ID that this gimbal manager is responsible for. Component ID of gimbal device (or 1-6 for non-MAVLink gimbal). - */ -static inline uint8_t mavlink_msg_gimbal_manager_status_get_gimbal_device_id(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 8); -} - -/** - * @brief Get field primary_control_sysid from gimbal_manager_status message - * - * @return System ID of MAVLink component with primary control, 0 for none. - */ -static inline uint8_t mavlink_msg_gimbal_manager_status_get_primary_control_sysid(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 9); -} - -/** - * @brief Get field primary_control_compid from gimbal_manager_status message - * - * @return Component ID of MAVLink component with primary control, 0 for none. - */ -static inline uint8_t mavlink_msg_gimbal_manager_status_get_primary_control_compid(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 10); -} - -/** - * @brief Get field secondary_control_sysid from gimbal_manager_status message - * - * @return System ID of MAVLink component with secondary control, 0 for none. - */ -static inline uint8_t mavlink_msg_gimbal_manager_status_get_secondary_control_sysid(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 11); -} - -/** - * @brief Get field secondary_control_compid from gimbal_manager_status message - * - * @return Component ID of MAVLink component with secondary control, 0 for none. - */ -static inline uint8_t mavlink_msg_gimbal_manager_status_get_secondary_control_compid(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 12); -} - -/** - * @brief Decode a gimbal_manager_status message into a struct - * - * @param msg The message to decode - * @param gimbal_manager_status C-struct to decode the message contents into - */ -static inline void mavlink_msg_gimbal_manager_status_decode(const mavlink_message_t* msg, mavlink_gimbal_manager_status_t* gimbal_manager_status) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - gimbal_manager_status->time_boot_ms = mavlink_msg_gimbal_manager_status_get_time_boot_ms(msg); - gimbal_manager_status->flags = mavlink_msg_gimbal_manager_status_get_flags(msg); - gimbal_manager_status->gimbal_device_id = mavlink_msg_gimbal_manager_status_get_gimbal_device_id(msg); - gimbal_manager_status->primary_control_sysid = mavlink_msg_gimbal_manager_status_get_primary_control_sysid(msg); - gimbal_manager_status->primary_control_compid = mavlink_msg_gimbal_manager_status_get_primary_control_compid(msg); - gimbal_manager_status->secondary_control_sysid = mavlink_msg_gimbal_manager_status_get_secondary_control_sysid(msg); - gimbal_manager_status->secondary_control_compid = mavlink_msg_gimbal_manager_status_get_secondary_control_compid(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_GIMBAL_MANAGER_STATUS_LEN? msg->len : MAVLINK_MSG_ID_GIMBAL_MANAGER_STATUS_LEN; - memset(gimbal_manager_status, 0, MAVLINK_MSG_ID_GIMBAL_MANAGER_STATUS_LEN); - memcpy(gimbal_manager_status, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_global_position_int.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_global_position_int.h deleted file mode 100644 index e30d87dc..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_global_position_int.h +++ /dev/null @@ -1,413 +0,0 @@ -#pragma once -// MESSAGE GLOBAL_POSITION_INT PACKING - -#define MAVLINK_MSG_ID_GLOBAL_POSITION_INT 33 - - -typedef struct __mavlink_global_position_int_t { - uint32_t time_boot_ms; /*< [ms] Timestamp (time since system boot).*/ - int32_t lat; /*< [degE7] Latitude, expressed*/ - int32_t lon; /*< [degE7] Longitude, expressed*/ - int32_t alt; /*< [mm] Altitude (MSL). Note that virtually all GPS modules provide both WGS84 and MSL.*/ - int32_t relative_alt; /*< [mm] Altitude above ground*/ - int16_t vx; /*< [cm/s] Ground X Speed (Latitude, positive north)*/ - int16_t vy; /*< [cm/s] Ground Y Speed (Longitude, positive east)*/ - int16_t vz; /*< [cm/s] Ground Z Speed (Altitude, positive down)*/ - uint16_t hdg; /*< [cdeg] Vehicle heading (yaw angle), 0.0..359.99 degrees. If unknown, set to: UINT16_MAX*/ -} mavlink_global_position_int_t; - -#define MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN 28 -#define MAVLINK_MSG_ID_GLOBAL_POSITION_INT_MIN_LEN 28 -#define MAVLINK_MSG_ID_33_LEN 28 -#define MAVLINK_MSG_ID_33_MIN_LEN 28 - -#define MAVLINK_MSG_ID_GLOBAL_POSITION_INT_CRC 104 -#define MAVLINK_MSG_ID_33_CRC 104 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT { \ - 33, \ - "GLOBAL_POSITION_INT", \ - 9, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_global_position_int_t, time_boot_ms) }, \ - { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_global_position_int_t, lat) }, \ - { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_global_position_int_t, lon) }, \ - { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_global_position_int_t, alt) }, \ - { "relative_alt", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_global_position_int_t, relative_alt) }, \ - { "vx", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_global_position_int_t, vx) }, \ - { "vy", NULL, MAVLINK_TYPE_INT16_T, 0, 22, offsetof(mavlink_global_position_int_t, vy) }, \ - { "vz", NULL, MAVLINK_TYPE_INT16_T, 0, 24, offsetof(mavlink_global_position_int_t, vz) }, \ - { "hdg", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_global_position_int_t, hdg) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT { \ - "GLOBAL_POSITION_INT", \ - 9, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_global_position_int_t, time_boot_ms) }, \ - { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_global_position_int_t, lat) }, \ - { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_global_position_int_t, lon) }, \ - { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_global_position_int_t, alt) }, \ - { "relative_alt", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_global_position_int_t, relative_alt) }, \ - { "vx", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_global_position_int_t, vx) }, \ - { "vy", NULL, MAVLINK_TYPE_INT16_T, 0, 22, offsetof(mavlink_global_position_int_t, vy) }, \ - { "vz", NULL, MAVLINK_TYPE_INT16_T, 0, 24, offsetof(mavlink_global_position_int_t, vz) }, \ - { "hdg", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_global_position_int_t, hdg) }, \ - } \ -} -#endif - -/** - * @brief Pack a global_position_int message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param time_boot_ms [ms] Timestamp (time since system boot). - * @param lat [degE7] Latitude, expressed - * @param lon [degE7] Longitude, expressed - * @param alt [mm] Altitude (MSL). Note that virtually all GPS modules provide both WGS84 and MSL. - * @param relative_alt [mm] Altitude above ground - * @param vx [cm/s] Ground X Speed (Latitude, positive north) - * @param vy [cm/s] Ground Y Speed (Longitude, positive east) - * @param vz [cm/s] Ground Z Speed (Altitude, positive down) - * @param hdg [cdeg] Vehicle heading (yaw angle), 0.0..359.99 degrees. If unknown, set to: UINT16_MAX - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_global_position_int_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint32_t time_boot_ms, int32_t lat, int32_t lon, int32_t alt, int32_t relative_alt, int16_t vx, int16_t vy, int16_t vz, uint16_t hdg) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_int32_t(buf, 4, lat); - _mav_put_int32_t(buf, 8, lon); - _mav_put_int32_t(buf, 12, alt); - _mav_put_int32_t(buf, 16, relative_alt); - _mav_put_int16_t(buf, 20, vx); - _mav_put_int16_t(buf, 22, vy); - _mav_put_int16_t(buf, 24, vz); - _mav_put_uint16_t(buf, 26, hdg); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN); -#else - mavlink_global_position_int_t packet; - packet.time_boot_ms = time_boot_ms; - packet.lat = lat; - packet.lon = lon; - packet.alt = alt; - packet.relative_alt = relative_alt; - packet.vx = vx; - packet.vy = vy; - packet.vz = vz; - packet.hdg = hdg; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_GLOBAL_POSITION_INT; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_MIN_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_CRC); -} - -/** - * @brief Pack a global_position_int message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_boot_ms [ms] Timestamp (time since system boot). - * @param lat [degE7] Latitude, expressed - * @param lon [degE7] Longitude, expressed - * @param alt [mm] Altitude (MSL). Note that virtually all GPS modules provide both WGS84 and MSL. - * @param relative_alt [mm] Altitude above ground - * @param vx [cm/s] Ground X Speed (Latitude, positive north) - * @param vy [cm/s] Ground Y Speed (Longitude, positive east) - * @param vz [cm/s] Ground Z Speed (Altitude, positive down) - * @param hdg [cdeg] Vehicle heading (yaw angle), 0.0..359.99 degrees. If unknown, set to: UINT16_MAX - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_global_position_int_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint32_t time_boot_ms,int32_t lat,int32_t lon,int32_t alt,int32_t relative_alt,int16_t vx,int16_t vy,int16_t vz,uint16_t hdg) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_int32_t(buf, 4, lat); - _mav_put_int32_t(buf, 8, lon); - _mav_put_int32_t(buf, 12, alt); - _mav_put_int32_t(buf, 16, relative_alt); - _mav_put_int16_t(buf, 20, vx); - _mav_put_int16_t(buf, 22, vy); - _mav_put_int16_t(buf, 24, vz); - _mav_put_uint16_t(buf, 26, hdg); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN); -#else - mavlink_global_position_int_t packet; - packet.time_boot_ms = time_boot_ms; - packet.lat = lat; - packet.lon = lon; - packet.alt = alt; - packet.relative_alt = relative_alt; - packet.vx = vx; - packet.vy = vy; - packet.vz = vz; - packet.hdg = hdg; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_GLOBAL_POSITION_INT; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_MIN_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_CRC); -} - -/** - * @brief Encode a global_position_int struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param global_position_int C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_global_position_int_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_global_position_int_t* global_position_int) -{ - return mavlink_msg_global_position_int_pack(system_id, component_id, msg, global_position_int->time_boot_ms, global_position_int->lat, global_position_int->lon, global_position_int->alt, global_position_int->relative_alt, global_position_int->vx, global_position_int->vy, global_position_int->vz, global_position_int->hdg); -} - -/** - * @brief Encode a global_position_int struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param global_position_int C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_global_position_int_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_global_position_int_t* global_position_int) -{ - return mavlink_msg_global_position_int_pack_chan(system_id, component_id, chan, msg, global_position_int->time_boot_ms, global_position_int->lat, global_position_int->lon, global_position_int->alt, global_position_int->relative_alt, global_position_int->vx, global_position_int->vy, global_position_int->vz, global_position_int->hdg); -} - -/** - * @brief Send a global_position_int message - * @param chan MAVLink channel to send the message - * - * @param time_boot_ms [ms] Timestamp (time since system boot). - * @param lat [degE7] Latitude, expressed - * @param lon [degE7] Longitude, expressed - * @param alt [mm] Altitude (MSL). Note that virtually all GPS modules provide both WGS84 and MSL. - * @param relative_alt [mm] Altitude above ground - * @param vx [cm/s] Ground X Speed (Latitude, positive north) - * @param vy [cm/s] Ground Y Speed (Longitude, positive east) - * @param vz [cm/s] Ground Z Speed (Altitude, positive down) - * @param hdg [cdeg] Vehicle heading (yaw angle), 0.0..359.99 degrees. If unknown, set to: UINT16_MAX - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_global_position_int_send(mavlink_channel_t chan, uint32_t time_boot_ms, int32_t lat, int32_t lon, int32_t alt, int32_t relative_alt, int16_t vx, int16_t vy, int16_t vz, uint16_t hdg) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_int32_t(buf, 4, lat); - _mav_put_int32_t(buf, 8, lon); - _mav_put_int32_t(buf, 12, alt); - _mav_put_int32_t(buf, 16, relative_alt); - _mav_put_int16_t(buf, 20, vx); - _mav_put_int16_t(buf, 22, vy); - _mav_put_int16_t(buf, 24, vz); - _mav_put_uint16_t(buf, 26, hdg); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT, buf, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_MIN_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_CRC); -#else - mavlink_global_position_int_t packet; - packet.time_boot_ms = time_boot_ms; - packet.lat = lat; - packet.lon = lon; - packet.alt = alt; - packet.relative_alt = relative_alt; - packet.vx = vx; - packet.vy = vy; - packet.vz = vz; - packet.hdg = hdg; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT, (const char *)&packet, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_MIN_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_CRC); -#endif -} - -/** - * @brief Send a global_position_int message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_global_position_int_send_struct(mavlink_channel_t chan, const mavlink_global_position_int_t* global_position_int) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_global_position_int_send(chan, global_position_int->time_boot_ms, global_position_int->lat, global_position_int->lon, global_position_int->alt, global_position_int->relative_alt, global_position_int->vx, global_position_int->vy, global_position_int->vz, global_position_int->hdg); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT, (const char *)global_position_int, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_MIN_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_CRC); -#endif -} - -#if MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_global_position_int_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, int32_t lat, int32_t lon, int32_t alt, int32_t relative_alt, int16_t vx, int16_t vy, int16_t vz, uint16_t hdg) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_int32_t(buf, 4, lat); - _mav_put_int32_t(buf, 8, lon); - _mav_put_int32_t(buf, 12, alt); - _mav_put_int32_t(buf, 16, relative_alt); - _mav_put_int16_t(buf, 20, vx); - _mav_put_int16_t(buf, 22, vy); - _mav_put_int16_t(buf, 24, vz); - _mav_put_uint16_t(buf, 26, hdg); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT, buf, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_MIN_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_CRC); -#else - mavlink_global_position_int_t *packet = (mavlink_global_position_int_t *)msgbuf; - packet->time_boot_ms = time_boot_ms; - packet->lat = lat; - packet->lon = lon; - packet->alt = alt; - packet->relative_alt = relative_alt; - packet->vx = vx; - packet->vy = vy; - packet->vz = vz; - packet->hdg = hdg; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT, (const char *)packet, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_MIN_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_CRC); -#endif -} -#endif - -#endif - -// MESSAGE GLOBAL_POSITION_INT UNPACKING - - -/** - * @brief Get field time_boot_ms from global_position_int message - * - * @return [ms] Timestamp (time since system boot). - */ -static inline uint32_t mavlink_msg_global_position_int_get_time_boot_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field lat from global_position_int message - * - * @return [degE7] Latitude, expressed - */ -static inline int32_t mavlink_msg_global_position_int_get_lat(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 4); -} - -/** - * @brief Get field lon from global_position_int message - * - * @return [degE7] Longitude, expressed - */ -static inline int32_t mavlink_msg_global_position_int_get_lon(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 8); -} - -/** - * @brief Get field alt from global_position_int message - * - * @return [mm] Altitude (MSL). Note that virtually all GPS modules provide both WGS84 and MSL. - */ -static inline int32_t mavlink_msg_global_position_int_get_alt(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 12); -} - -/** - * @brief Get field relative_alt from global_position_int message - * - * @return [mm] Altitude above ground - */ -static inline int32_t mavlink_msg_global_position_int_get_relative_alt(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 16); -} - -/** - * @brief Get field vx from global_position_int message - * - * @return [cm/s] Ground X Speed (Latitude, positive north) - */ -static inline int16_t mavlink_msg_global_position_int_get_vx(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 20); -} - -/** - * @brief Get field vy from global_position_int message - * - * @return [cm/s] Ground Y Speed (Longitude, positive east) - */ -static inline int16_t mavlink_msg_global_position_int_get_vy(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 22); -} - -/** - * @brief Get field vz from global_position_int message - * - * @return [cm/s] Ground Z Speed (Altitude, positive down) - */ -static inline int16_t mavlink_msg_global_position_int_get_vz(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 24); -} - -/** - * @brief Get field hdg from global_position_int message - * - * @return [cdeg] Vehicle heading (yaw angle), 0.0..359.99 degrees. If unknown, set to: UINT16_MAX - */ -static inline uint16_t mavlink_msg_global_position_int_get_hdg(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 26); -} - -/** - * @brief Decode a global_position_int message into a struct - * - * @param msg The message to decode - * @param global_position_int C-struct to decode the message contents into - */ -static inline void mavlink_msg_global_position_int_decode(const mavlink_message_t* msg, mavlink_global_position_int_t* global_position_int) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - global_position_int->time_boot_ms = mavlink_msg_global_position_int_get_time_boot_ms(msg); - global_position_int->lat = mavlink_msg_global_position_int_get_lat(msg); - global_position_int->lon = mavlink_msg_global_position_int_get_lon(msg); - global_position_int->alt = mavlink_msg_global_position_int_get_alt(msg); - global_position_int->relative_alt = mavlink_msg_global_position_int_get_relative_alt(msg); - global_position_int->vx = mavlink_msg_global_position_int_get_vx(msg); - global_position_int->vy = mavlink_msg_global_position_int_get_vy(msg); - global_position_int->vz = mavlink_msg_global_position_int_get_vz(msg); - global_position_int->hdg = mavlink_msg_global_position_int_get_hdg(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN? msg->len : MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN; - memset(global_position_int, 0, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN); - memcpy(global_position_int, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_global_position_int_cov.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_global_position_int_cov.h deleted file mode 100644 index 89f4c646..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_global_position_int_cov.h +++ /dev/null @@ -1,430 +0,0 @@ -#pragma once -// MESSAGE GLOBAL_POSITION_INT_COV PACKING - -#define MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV 63 - - -typedef struct __mavlink_global_position_int_cov_t { - uint64_t time_usec; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/ - int32_t lat; /*< [degE7] Latitude*/ - int32_t lon; /*< [degE7] Longitude*/ - int32_t alt; /*< [mm] Altitude in meters above MSL*/ - int32_t relative_alt; /*< [mm] Altitude above ground*/ - float vx; /*< [m/s] Ground X Speed (Latitude)*/ - float vy; /*< [m/s] Ground Y Speed (Longitude)*/ - float vz; /*< [m/s] Ground Z Speed (Altitude)*/ - float covariance[36]; /*< Row-major representation of a 6x6 position and velocity 6x6 cross-covariance matrix (states: lat, lon, alt, vx, vy, vz; first six entries are the first ROW, next six entries are the second row, etc.). If unknown, assign NaN value to first element in the array.*/ - uint8_t estimator_type; /*< Class id of the estimator this estimate originated from.*/ -} mavlink_global_position_int_cov_t; - -#define MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN 181 -#define MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_MIN_LEN 181 -#define MAVLINK_MSG_ID_63_LEN 181 -#define MAVLINK_MSG_ID_63_MIN_LEN 181 - -#define MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_CRC 119 -#define MAVLINK_MSG_ID_63_CRC 119 - -#define MAVLINK_MSG_GLOBAL_POSITION_INT_COV_FIELD_COVARIANCE_LEN 36 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT_COV { \ - 63, \ - "GLOBAL_POSITION_INT_COV", \ - 10, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_global_position_int_cov_t, time_usec) }, \ - { "estimator_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 180, offsetof(mavlink_global_position_int_cov_t, estimator_type) }, \ - { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_global_position_int_cov_t, lat) }, \ - { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_global_position_int_cov_t, lon) }, \ - { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_global_position_int_cov_t, alt) }, \ - { "relative_alt", NULL, MAVLINK_TYPE_INT32_T, 0, 20, offsetof(mavlink_global_position_int_cov_t, relative_alt) }, \ - { "vx", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_global_position_int_cov_t, vx) }, \ - { "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_global_position_int_cov_t, vy) }, \ - { "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_global_position_int_cov_t, vz) }, \ - { "covariance", NULL, MAVLINK_TYPE_FLOAT, 36, 36, offsetof(mavlink_global_position_int_cov_t, covariance) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT_COV { \ - "GLOBAL_POSITION_INT_COV", \ - 10, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_global_position_int_cov_t, time_usec) }, \ - { "estimator_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 180, offsetof(mavlink_global_position_int_cov_t, estimator_type) }, \ - { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_global_position_int_cov_t, lat) }, \ - { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_global_position_int_cov_t, lon) }, \ - { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_global_position_int_cov_t, alt) }, \ - { "relative_alt", NULL, MAVLINK_TYPE_INT32_T, 0, 20, offsetof(mavlink_global_position_int_cov_t, relative_alt) }, \ - { "vx", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_global_position_int_cov_t, vx) }, \ - { "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_global_position_int_cov_t, vy) }, \ - { "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_global_position_int_cov_t, vz) }, \ - { "covariance", NULL, MAVLINK_TYPE_FLOAT, 36, 36, offsetof(mavlink_global_position_int_cov_t, covariance) }, \ - } \ -} -#endif - -/** - * @brief Pack a global_position_int_cov message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @param estimator_type Class id of the estimator this estimate originated from. - * @param lat [degE7] Latitude - * @param lon [degE7] Longitude - * @param alt [mm] Altitude in meters above MSL - * @param relative_alt [mm] Altitude above ground - * @param vx [m/s] Ground X Speed (Latitude) - * @param vy [m/s] Ground Y Speed (Longitude) - * @param vz [m/s] Ground Z Speed (Altitude) - * @param covariance Row-major representation of a 6x6 position and velocity 6x6 cross-covariance matrix (states: lat, lon, alt, vx, vy, vz; first six entries are the first ROW, next six entries are the second row, etc.). If unknown, assign NaN value to first element in the array. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_global_position_int_cov_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint64_t time_usec, uint8_t estimator_type, int32_t lat, int32_t lon, int32_t alt, int32_t relative_alt, float vx, float vy, float vz, const float *covariance) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_int32_t(buf, 8, lat); - _mav_put_int32_t(buf, 12, lon); - _mav_put_int32_t(buf, 16, alt); - _mav_put_int32_t(buf, 20, relative_alt); - _mav_put_float(buf, 24, vx); - _mav_put_float(buf, 28, vy); - _mav_put_float(buf, 32, vz); - _mav_put_uint8_t(buf, 180, estimator_type); - _mav_put_float_array(buf, 36, covariance, 36); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN); -#else - mavlink_global_position_int_cov_t packet; - packet.time_usec = time_usec; - packet.lat = lat; - packet.lon = lon; - packet.alt = alt; - packet.relative_alt = relative_alt; - packet.vx = vx; - packet.vy = vy; - packet.vz = vz; - packet.estimator_type = estimator_type; - mav_array_memcpy(packet.covariance, covariance, sizeof(float)*36); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_MIN_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_CRC); -} - -/** - * @brief Pack a global_position_int_cov message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @param estimator_type Class id of the estimator this estimate originated from. - * @param lat [degE7] Latitude - * @param lon [degE7] Longitude - * @param alt [mm] Altitude in meters above MSL - * @param relative_alt [mm] Altitude above ground - * @param vx [m/s] Ground X Speed (Latitude) - * @param vy [m/s] Ground Y Speed (Longitude) - * @param vz [m/s] Ground Z Speed (Altitude) - * @param covariance Row-major representation of a 6x6 position and velocity 6x6 cross-covariance matrix (states: lat, lon, alt, vx, vy, vz; first six entries are the first ROW, next six entries are the second row, etc.). If unknown, assign NaN value to first element in the array. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_global_position_int_cov_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint64_t time_usec,uint8_t estimator_type,int32_t lat,int32_t lon,int32_t alt,int32_t relative_alt,float vx,float vy,float vz,const float *covariance) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_int32_t(buf, 8, lat); - _mav_put_int32_t(buf, 12, lon); - _mav_put_int32_t(buf, 16, alt); - _mav_put_int32_t(buf, 20, relative_alt); - _mav_put_float(buf, 24, vx); - _mav_put_float(buf, 28, vy); - _mav_put_float(buf, 32, vz); - _mav_put_uint8_t(buf, 180, estimator_type); - _mav_put_float_array(buf, 36, covariance, 36); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN); -#else - mavlink_global_position_int_cov_t packet; - packet.time_usec = time_usec; - packet.lat = lat; - packet.lon = lon; - packet.alt = alt; - packet.relative_alt = relative_alt; - packet.vx = vx; - packet.vy = vy; - packet.vz = vz; - packet.estimator_type = estimator_type; - mav_array_memcpy(packet.covariance, covariance, sizeof(float)*36); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_MIN_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_CRC); -} - -/** - * @brief Encode a global_position_int_cov struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param global_position_int_cov C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_global_position_int_cov_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_global_position_int_cov_t* global_position_int_cov) -{ - return mavlink_msg_global_position_int_cov_pack(system_id, component_id, msg, global_position_int_cov->time_usec, global_position_int_cov->estimator_type, global_position_int_cov->lat, global_position_int_cov->lon, global_position_int_cov->alt, global_position_int_cov->relative_alt, global_position_int_cov->vx, global_position_int_cov->vy, global_position_int_cov->vz, global_position_int_cov->covariance); -} - -/** - * @brief Encode a global_position_int_cov struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param global_position_int_cov C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_global_position_int_cov_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_global_position_int_cov_t* global_position_int_cov) -{ - return mavlink_msg_global_position_int_cov_pack_chan(system_id, component_id, chan, msg, global_position_int_cov->time_usec, global_position_int_cov->estimator_type, global_position_int_cov->lat, global_position_int_cov->lon, global_position_int_cov->alt, global_position_int_cov->relative_alt, global_position_int_cov->vx, global_position_int_cov->vy, global_position_int_cov->vz, global_position_int_cov->covariance); -} - -/** - * @brief Send a global_position_int_cov message - * @param chan MAVLink channel to send the message - * - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @param estimator_type Class id of the estimator this estimate originated from. - * @param lat [degE7] Latitude - * @param lon [degE7] Longitude - * @param alt [mm] Altitude in meters above MSL - * @param relative_alt [mm] Altitude above ground - * @param vx [m/s] Ground X Speed (Latitude) - * @param vy [m/s] Ground Y Speed (Longitude) - * @param vz [m/s] Ground Z Speed (Altitude) - * @param covariance Row-major representation of a 6x6 position and velocity 6x6 cross-covariance matrix (states: lat, lon, alt, vx, vy, vz; first six entries are the first ROW, next six entries are the second row, etc.). If unknown, assign NaN value to first element in the array. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_global_position_int_cov_send(mavlink_channel_t chan, uint64_t time_usec, uint8_t estimator_type, int32_t lat, int32_t lon, int32_t alt, int32_t relative_alt, float vx, float vy, float vz, const float *covariance) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_int32_t(buf, 8, lat); - _mav_put_int32_t(buf, 12, lon); - _mav_put_int32_t(buf, 16, alt); - _mav_put_int32_t(buf, 20, relative_alt); - _mav_put_float(buf, 24, vx); - _mav_put_float(buf, 28, vy); - _mav_put_float(buf, 32, vz); - _mav_put_uint8_t(buf, 180, estimator_type); - _mav_put_float_array(buf, 36, covariance, 36); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV, buf, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_MIN_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_CRC); -#else - mavlink_global_position_int_cov_t packet; - packet.time_usec = time_usec; - packet.lat = lat; - packet.lon = lon; - packet.alt = alt; - packet.relative_alt = relative_alt; - packet.vx = vx; - packet.vy = vy; - packet.vz = vz; - packet.estimator_type = estimator_type; - mav_array_memcpy(packet.covariance, covariance, sizeof(float)*36); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV, (const char *)&packet, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_MIN_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_CRC); -#endif -} - -/** - * @brief Send a global_position_int_cov message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_global_position_int_cov_send_struct(mavlink_channel_t chan, const mavlink_global_position_int_cov_t* global_position_int_cov) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_global_position_int_cov_send(chan, global_position_int_cov->time_usec, global_position_int_cov->estimator_type, global_position_int_cov->lat, global_position_int_cov->lon, global_position_int_cov->alt, global_position_int_cov->relative_alt, global_position_int_cov->vx, global_position_int_cov->vy, global_position_int_cov->vz, global_position_int_cov->covariance); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV, (const char *)global_position_int_cov, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_MIN_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_CRC); -#endif -} - -#if MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_global_position_int_cov_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, uint8_t estimator_type, int32_t lat, int32_t lon, int32_t alt, int32_t relative_alt, float vx, float vy, float vz, const float *covariance) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_int32_t(buf, 8, lat); - _mav_put_int32_t(buf, 12, lon); - _mav_put_int32_t(buf, 16, alt); - _mav_put_int32_t(buf, 20, relative_alt); - _mav_put_float(buf, 24, vx); - _mav_put_float(buf, 28, vy); - _mav_put_float(buf, 32, vz); - _mav_put_uint8_t(buf, 180, estimator_type); - _mav_put_float_array(buf, 36, covariance, 36); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV, buf, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_MIN_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_CRC); -#else - mavlink_global_position_int_cov_t *packet = (mavlink_global_position_int_cov_t *)msgbuf; - packet->time_usec = time_usec; - packet->lat = lat; - packet->lon = lon; - packet->alt = alt; - packet->relative_alt = relative_alt; - packet->vx = vx; - packet->vy = vy; - packet->vz = vz; - packet->estimator_type = estimator_type; - mav_array_memcpy(packet->covariance, covariance, sizeof(float)*36); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV, (const char *)packet, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_MIN_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_CRC); -#endif -} -#endif - -#endif - -// MESSAGE GLOBAL_POSITION_INT_COV UNPACKING - - -/** - * @brief Get field time_usec from global_position_int_cov message - * - * @return [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - */ -static inline uint64_t mavlink_msg_global_position_int_cov_get_time_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field estimator_type from global_position_int_cov message - * - * @return Class id of the estimator this estimate originated from. - */ -static inline uint8_t mavlink_msg_global_position_int_cov_get_estimator_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 180); -} - -/** - * @brief Get field lat from global_position_int_cov message - * - * @return [degE7] Latitude - */ -static inline int32_t mavlink_msg_global_position_int_cov_get_lat(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 8); -} - -/** - * @brief Get field lon from global_position_int_cov message - * - * @return [degE7] Longitude - */ -static inline int32_t mavlink_msg_global_position_int_cov_get_lon(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 12); -} - -/** - * @brief Get field alt from global_position_int_cov message - * - * @return [mm] Altitude in meters above MSL - */ -static inline int32_t mavlink_msg_global_position_int_cov_get_alt(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 16); -} - -/** - * @brief Get field relative_alt from global_position_int_cov message - * - * @return [mm] Altitude above ground - */ -static inline int32_t mavlink_msg_global_position_int_cov_get_relative_alt(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 20); -} - -/** - * @brief Get field vx from global_position_int_cov message - * - * @return [m/s] Ground X Speed (Latitude) - */ -static inline float mavlink_msg_global_position_int_cov_get_vx(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Get field vy from global_position_int_cov message - * - * @return [m/s] Ground Y Speed (Longitude) - */ -static inline float mavlink_msg_global_position_int_cov_get_vy(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 28); -} - -/** - * @brief Get field vz from global_position_int_cov message - * - * @return [m/s] Ground Z Speed (Altitude) - */ -static inline float mavlink_msg_global_position_int_cov_get_vz(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 32); -} - -/** - * @brief Get field covariance from global_position_int_cov message - * - * @return Row-major representation of a 6x6 position and velocity 6x6 cross-covariance matrix (states: lat, lon, alt, vx, vy, vz; first six entries are the first ROW, next six entries are the second row, etc.). If unknown, assign NaN value to first element in the array. - */ -static inline uint16_t mavlink_msg_global_position_int_cov_get_covariance(const mavlink_message_t* msg, float *covariance) -{ - return _MAV_RETURN_float_array(msg, covariance, 36, 36); -} - -/** - * @brief Decode a global_position_int_cov message into a struct - * - * @param msg The message to decode - * @param global_position_int_cov C-struct to decode the message contents into - */ -static inline void mavlink_msg_global_position_int_cov_decode(const mavlink_message_t* msg, mavlink_global_position_int_cov_t* global_position_int_cov) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - global_position_int_cov->time_usec = mavlink_msg_global_position_int_cov_get_time_usec(msg); - global_position_int_cov->lat = mavlink_msg_global_position_int_cov_get_lat(msg); - global_position_int_cov->lon = mavlink_msg_global_position_int_cov_get_lon(msg); - global_position_int_cov->alt = mavlink_msg_global_position_int_cov_get_alt(msg); - global_position_int_cov->relative_alt = mavlink_msg_global_position_int_cov_get_relative_alt(msg); - global_position_int_cov->vx = mavlink_msg_global_position_int_cov_get_vx(msg); - global_position_int_cov->vy = mavlink_msg_global_position_int_cov_get_vy(msg); - global_position_int_cov->vz = mavlink_msg_global_position_int_cov_get_vz(msg); - mavlink_msg_global_position_int_cov_get_covariance(msg, global_position_int_cov->covariance); - global_position_int_cov->estimator_type = mavlink_msg_global_position_int_cov_get_estimator_type(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN? msg->len : MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN; - memset(global_position_int_cov, 0, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN); - memcpy(global_position_int_cov, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_global_vision_position_estimate.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_global_vision_position_estimate.h deleted file mode 100644 index b2dee2ec..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_global_vision_position_estimate.h +++ /dev/null @@ -1,405 +0,0 @@ -#pragma once -// MESSAGE GLOBAL_VISION_POSITION_ESTIMATE PACKING - -#define MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE 101 - - -typedef struct __mavlink_global_vision_position_estimate_t { - uint64_t usec; /*< [us] Timestamp (UNIX time or since system boot)*/ - float x; /*< [m] Global X position*/ - float y; /*< [m] Global Y position*/ - float z; /*< [m] Global Z position*/ - float roll; /*< [rad] Roll angle*/ - float pitch; /*< [rad] Pitch angle*/ - float yaw; /*< [rad] Yaw angle*/ - float covariance[21]; /*< Row-major representation of pose 6x6 cross-covariance matrix upper right triangle (states: x_global, y_global, z_global, roll, pitch, yaw; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array.*/ - uint8_t reset_counter; /*< Estimate reset counter. This should be incremented when the estimate resets in any of the dimensions (position, velocity, attitude, angular speed). This is designed to be used when e.g an external SLAM system detects a loop-closure and the estimate jumps.*/ -} mavlink_global_vision_position_estimate_t; - -#define MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN 117 -#define MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_MIN_LEN 32 -#define MAVLINK_MSG_ID_101_LEN 117 -#define MAVLINK_MSG_ID_101_MIN_LEN 32 - -#define MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_CRC 102 -#define MAVLINK_MSG_ID_101_CRC 102 - -#define MAVLINK_MSG_GLOBAL_VISION_POSITION_ESTIMATE_FIELD_COVARIANCE_LEN 21 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_GLOBAL_VISION_POSITION_ESTIMATE { \ - 101, \ - "GLOBAL_VISION_POSITION_ESTIMATE", \ - 9, \ - { { "usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_global_vision_position_estimate_t, usec) }, \ - { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_global_vision_position_estimate_t, x) }, \ - { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_global_vision_position_estimate_t, y) }, \ - { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_global_vision_position_estimate_t, z) }, \ - { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_global_vision_position_estimate_t, roll) }, \ - { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_global_vision_position_estimate_t, pitch) }, \ - { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_global_vision_position_estimate_t, yaw) }, \ - { "covariance", NULL, MAVLINK_TYPE_FLOAT, 21, 32, offsetof(mavlink_global_vision_position_estimate_t, covariance) }, \ - { "reset_counter", NULL, MAVLINK_TYPE_UINT8_T, 0, 116, offsetof(mavlink_global_vision_position_estimate_t, reset_counter) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_GLOBAL_VISION_POSITION_ESTIMATE { \ - "GLOBAL_VISION_POSITION_ESTIMATE", \ - 9, \ - { { "usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_global_vision_position_estimate_t, usec) }, \ - { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_global_vision_position_estimate_t, x) }, \ - { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_global_vision_position_estimate_t, y) }, \ - { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_global_vision_position_estimate_t, z) }, \ - { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_global_vision_position_estimate_t, roll) }, \ - { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_global_vision_position_estimate_t, pitch) }, \ - { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_global_vision_position_estimate_t, yaw) }, \ - { "covariance", NULL, MAVLINK_TYPE_FLOAT, 21, 32, offsetof(mavlink_global_vision_position_estimate_t, covariance) }, \ - { "reset_counter", NULL, MAVLINK_TYPE_UINT8_T, 0, 116, offsetof(mavlink_global_vision_position_estimate_t, reset_counter) }, \ - } \ -} -#endif - -/** - * @brief Pack a global_vision_position_estimate message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param usec [us] Timestamp (UNIX time or since system boot) - * @param x [m] Global X position - * @param y [m] Global Y position - * @param z [m] Global Z position - * @param roll [rad] Roll angle - * @param pitch [rad] Pitch angle - * @param yaw [rad] Yaw angle - * @param covariance Row-major representation of pose 6x6 cross-covariance matrix upper right triangle (states: x_global, y_global, z_global, roll, pitch, yaw; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array. - * @param reset_counter Estimate reset counter. This should be incremented when the estimate resets in any of the dimensions (position, velocity, attitude, angular speed). This is designed to be used when e.g an external SLAM system detects a loop-closure and the estimate jumps. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_global_vision_position_estimate_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint64_t usec, float x, float y, float z, float roll, float pitch, float yaw, const float *covariance, uint8_t reset_counter) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN]; - _mav_put_uint64_t(buf, 0, usec); - _mav_put_float(buf, 8, x); - _mav_put_float(buf, 12, y); - _mav_put_float(buf, 16, z); - _mav_put_float(buf, 20, roll); - _mav_put_float(buf, 24, pitch); - _mav_put_float(buf, 28, yaw); - _mav_put_uint8_t(buf, 116, reset_counter); - _mav_put_float_array(buf, 32, covariance, 21); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN); -#else - mavlink_global_vision_position_estimate_t packet; - packet.usec = usec; - packet.x = x; - packet.y = y; - packet.z = z; - packet.roll = roll; - packet.pitch = pitch; - packet.yaw = yaw; - packet.reset_counter = reset_counter; - mav_array_memcpy(packet.covariance, covariance, sizeof(float)*21); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_MIN_LEN, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_CRC); -} - -/** - * @brief Pack a global_vision_position_estimate message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param usec [us] Timestamp (UNIX time or since system boot) - * @param x [m] Global X position - * @param y [m] Global Y position - * @param z [m] Global Z position - * @param roll [rad] Roll angle - * @param pitch [rad] Pitch angle - * @param yaw [rad] Yaw angle - * @param covariance Row-major representation of pose 6x6 cross-covariance matrix upper right triangle (states: x_global, y_global, z_global, roll, pitch, yaw; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array. - * @param reset_counter Estimate reset counter. This should be incremented when the estimate resets in any of the dimensions (position, velocity, attitude, angular speed). This is designed to be used when e.g an external SLAM system detects a loop-closure and the estimate jumps. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_global_vision_position_estimate_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint64_t usec,float x,float y,float z,float roll,float pitch,float yaw,const float *covariance,uint8_t reset_counter) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN]; - _mav_put_uint64_t(buf, 0, usec); - _mav_put_float(buf, 8, x); - _mav_put_float(buf, 12, y); - _mav_put_float(buf, 16, z); - _mav_put_float(buf, 20, roll); - _mav_put_float(buf, 24, pitch); - _mav_put_float(buf, 28, yaw); - _mav_put_uint8_t(buf, 116, reset_counter); - _mav_put_float_array(buf, 32, covariance, 21); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN); -#else - mavlink_global_vision_position_estimate_t packet; - packet.usec = usec; - packet.x = x; - packet.y = y; - packet.z = z; - packet.roll = roll; - packet.pitch = pitch; - packet.yaw = yaw; - packet.reset_counter = reset_counter; - mav_array_memcpy(packet.covariance, covariance, sizeof(float)*21); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_MIN_LEN, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_CRC); -} - -/** - * @brief Encode a global_vision_position_estimate struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param global_vision_position_estimate C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_global_vision_position_estimate_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_global_vision_position_estimate_t* global_vision_position_estimate) -{ - return mavlink_msg_global_vision_position_estimate_pack(system_id, component_id, msg, global_vision_position_estimate->usec, global_vision_position_estimate->x, global_vision_position_estimate->y, global_vision_position_estimate->z, global_vision_position_estimate->roll, global_vision_position_estimate->pitch, global_vision_position_estimate->yaw, global_vision_position_estimate->covariance, global_vision_position_estimate->reset_counter); -} - -/** - * @brief Encode a global_vision_position_estimate struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param global_vision_position_estimate C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_global_vision_position_estimate_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_global_vision_position_estimate_t* global_vision_position_estimate) -{ - return mavlink_msg_global_vision_position_estimate_pack_chan(system_id, component_id, chan, msg, global_vision_position_estimate->usec, global_vision_position_estimate->x, global_vision_position_estimate->y, global_vision_position_estimate->z, global_vision_position_estimate->roll, global_vision_position_estimate->pitch, global_vision_position_estimate->yaw, global_vision_position_estimate->covariance, global_vision_position_estimate->reset_counter); -} - -/** - * @brief Send a global_vision_position_estimate message - * @param chan MAVLink channel to send the message - * - * @param usec [us] Timestamp (UNIX time or since system boot) - * @param x [m] Global X position - * @param y [m] Global Y position - * @param z [m] Global Z position - * @param roll [rad] Roll angle - * @param pitch [rad] Pitch angle - * @param yaw [rad] Yaw angle - * @param covariance Row-major representation of pose 6x6 cross-covariance matrix upper right triangle (states: x_global, y_global, z_global, roll, pitch, yaw; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array. - * @param reset_counter Estimate reset counter. This should be incremented when the estimate resets in any of the dimensions (position, velocity, attitude, angular speed). This is designed to be used when e.g an external SLAM system detects a loop-closure and the estimate jumps. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_global_vision_position_estimate_send(mavlink_channel_t chan, uint64_t usec, float x, float y, float z, float roll, float pitch, float yaw, const float *covariance, uint8_t reset_counter) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN]; - _mav_put_uint64_t(buf, 0, usec); - _mav_put_float(buf, 8, x); - _mav_put_float(buf, 12, y); - _mav_put_float(buf, 16, z); - _mav_put_float(buf, 20, roll); - _mav_put_float(buf, 24, pitch); - _mav_put_float(buf, 28, yaw); - _mav_put_uint8_t(buf, 116, reset_counter); - _mav_put_float_array(buf, 32, covariance, 21); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE, buf, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_MIN_LEN, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_CRC); -#else - mavlink_global_vision_position_estimate_t packet; - packet.usec = usec; - packet.x = x; - packet.y = y; - packet.z = z; - packet.roll = roll; - packet.pitch = pitch; - packet.yaw = yaw; - packet.reset_counter = reset_counter; - mav_array_memcpy(packet.covariance, covariance, sizeof(float)*21); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE, (const char *)&packet, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_MIN_LEN, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_CRC); -#endif -} - -/** - * @brief Send a global_vision_position_estimate message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_global_vision_position_estimate_send_struct(mavlink_channel_t chan, const mavlink_global_vision_position_estimate_t* global_vision_position_estimate) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_global_vision_position_estimate_send(chan, global_vision_position_estimate->usec, global_vision_position_estimate->x, global_vision_position_estimate->y, global_vision_position_estimate->z, global_vision_position_estimate->roll, global_vision_position_estimate->pitch, global_vision_position_estimate->yaw, global_vision_position_estimate->covariance, global_vision_position_estimate->reset_counter); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE, (const char *)global_vision_position_estimate, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_MIN_LEN, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_CRC); -#endif -} - -#if MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_global_vision_position_estimate_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t usec, float x, float y, float z, float roll, float pitch, float yaw, const float *covariance, uint8_t reset_counter) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, usec); - _mav_put_float(buf, 8, x); - _mav_put_float(buf, 12, y); - _mav_put_float(buf, 16, z); - _mav_put_float(buf, 20, roll); - _mav_put_float(buf, 24, pitch); - _mav_put_float(buf, 28, yaw); - _mav_put_uint8_t(buf, 116, reset_counter); - _mav_put_float_array(buf, 32, covariance, 21); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE, buf, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_MIN_LEN, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_CRC); -#else - mavlink_global_vision_position_estimate_t *packet = (mavlink_global_vision_position_estimate_t *)msgbuf; - packet->usec = usec; - packet->x = x; - packet->y = y; - packet->z = z; - packet->roll = roll; - packet->pitch = pitch; - packet->yaw = yaw; - packet->reset_counter = reset_counter; - mav_array_memcpy(packet->covariance, covariance, sizeof(float)*21); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE, (const char *)packet, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_MIN_LEN, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_CRC); -#endif -} -#endif - -#endif - -// MESSAGE GLOBAL_VISION_POSITION_ESTIMATE UNPACKING - - -/** - * @brief Get field usec from global_vision_position_estimate message - * - * @return [us] Timestamp (UNIX time or since system boot) - */ -static inline uint64_t mavlink_msg_global_vision_position_estimate_get_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field x from global_vision_position_estimate message - * - * @return [m] Global X position - */ -static inline float mavlink_msg_global_vision_position_estimate_get_x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field y from global_vision_position_estimate message - * - * @return [m] Global Y position - */ -static inline float mavlink_msg_global_vision_position_estimate_get_y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field z from global_vision_position_estimate message - * - * @return [m] Global Z position - */ -static inline float mavlink_msg_global_vision_position_estimate_get_z(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field roll from global_vision_position_estimate message - * - * @return [rad] Roll angle - */ -static inline float mavlink_msg_global_vision_position_estimate_get_roll(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Get field pitch from global_vision_position_estimate message - * - * @return [rad] Pitch angle - */ -static inline float mavlink_msg_global_vision_position_estimate_get_pitch(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Get field yaw from global_vision_position_estimate message - * - * @return [rad] Yaw angle - */ -static inline float mavlink_msg_global_vision_position_estimate_get_yaw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 28); -} - -/** - * @brief Get field covariance from global_vision_position_estimate message - * - * @return Row-major representation of pose 6x6 cross-covariance matrix upper right triangle (states: x_global, y_global, z_global, roll, pitch, yaw; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array. - */ -static inline uint16_t mavlink_msg_global_vision_position_estimate_get_covariance(const mavlink_message_t* msg, float *covariance) -{ - return _MAV_RETURN_float_array(msg, covariance, 21, 32); -} - -/** - * @brief Get field reset_counter from global_vision_position_estimate message - * - * @return Estimate reset counter. This should be incremented when the estimate resets in any of the dimensions (position, velocity, attitude, angular speed). This is designed to be used when e.g an external SLAM system detects a loop-closure and the estimate jumps. - */ -static inline uint8_t mavlink_msg_global_vision_position_estimate_get_reset_counter(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 116); -} - -/** - * @brief Decode a global_vision_position_estimate message into a struct - * - * @param msg The message to decode - * @param global_vision_position_estimate C-struct to decode the message contents into - */ -static inline void mavlink_msg_global_vision_position_estimate_decode(const mavlink_message_t* msg, mavlink_global_vision_position_estimate_t* global_vision_position_estimate) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - global_vision_position_estimate->usec = mavlink_msg_global_vision_position_estimate_get_usec(msg); - global_vision_position_estimate->x = mavlink_msg_global_vision_position_estimate_get_x(msg); - global_vision_position_estimate->y = mavlink_msg_global_vision_position_estimate_get_y(msg); - global_vision_position_estimate->z = mavlink_msg_global_vision_position_estimate_get_z(msg); - global_vision_position_estimate->roll = mavlink_msg_global_vision_position_estimate_get_roll(msg); - global_vision_position_estimate->pitch = mavlink_msg_global_vision_position_estimate_get_pitch(msg); - global_vision_position_estimate->yaw = mavlink_msg_global_vision_position_estimate_get_yaw(msg); - mavlink_msg_global_vision_position_estimate_get_covariance(msg, global_vision_position_estimate->covariance); - global_vision_position_estimate->reset_counter = mavlink_msg_global_vision_position_estimate_get_reset_counter(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN? msg->len : MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN; - memset(global_vision_position_estimate, 0, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN); - memcpy(global_vision_position_estimate, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_gps2_raw.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_gps2_raw.h deleted file mode 100644 index aa7bdfa0..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_gps2_raw.h +++ /dev/null @@ -1,638 +0,0 @@ -#pragma once -// MESSAGE GPS2_RAW PACKING - -#define MAVLINK_MSG_ID_GPS2_RAW 124 - -MAVPACKED( -typedef struct __mavlink_gps2_raw_t { - uint64_t time_usec; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/ - int32_t lat; /*< [degE7] Latitude (WGS84)*/ - int32_t lon; /*< [degE7] Longitude (WGS84)*/ - int32_t alt; /*< [mm] Altitude (MSL). Positive for up.*/ - uint32_t dgps_age; /*< [ms] Age of DGPS info*/ - uint16_t eph; /*< GPS HDOP horizontal dilution of position (unitless * 100). If unknown, set to: UINT16_MAX*/ - uint16_t epv; /*< GPS VDOP vertical dilution of position (unitless * 100). If unknown, set to: UINT16_MAX*/ - uint16_t vel; /*< [cm/s] GPS ground speed. If unknown, set to: UINT16_MAX*/ - uint16_t cog; /*< [cdeg] Course over ground (NOT heading, but direction of movement): 0.0..359.99 degrees. If unknown, set to: UINT16_MAX*/ - uint8_t fix_type; /*< GPS fix type.*/ - uint8_t satellites_visible; /*< Number of satellites visible. If unknown, set to UINT8_MAX*/ - uint8_t dgps_numch; /*< Number of DGPS satellites*/ - uint16_t yaw; /*< [cdeg] Yaw in earth frame from north. Use 0 if this GPS does not provide yaw. Use UINT16_MAX if this GPS is configured to provide yaw and is currently unable to provide it. Use 36000 for north.*/ - int32_t alt_ellipsoid; /*< [mm] Altitude (above WGS84, EGM96 ellipsoid). Positive for up.*/ - uint32_t h_acc; /*< [mm] Position uncertainty.*/ - uint32_t v_acc; /*< [mm] Altitude uncertainty.*/ - uint32_t vel_acc; /*< [mm] Speed uncertainty.*/ - uint32_t hdg_acc; /*< [degE5] Heading / track uncertainty*/ -}) mavlink_gps2_raw_t; - -#define MAVLINK_MSG_ID_GPS2_RAW_LEN 57 -#define MAVLINK_MSG_ID_GPS2_RAW_MIN_LEN 35 -#define MAVLINK_MSG_ID_124_LEN 57 -#define MAVLINK_MSG_ID_124_MIN_LEN 35 - -#define MAVLINK_MSG_ID_GPS2_RAW_CRC 87 -#define MAVLINK_MSG_ID_124_CRC 87 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_GPS2_RAW { \ - 124, \ - "GPS2_RAW", \ - 18, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_gps2_raw_t, time_usec) }, \ - { "fix_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_gps2_raw_t, fix_type) }, \ - { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_gps2_raw_t, lat) }, \ - { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_gps2_raw_t, lon) }, \ - { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_gps2_raw_t, alt) }, \ - { "eph", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_gps2_raw_t, eph) }, \ - { "epv", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_gps2_raw_t, epv) }, \ - { "vel", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_gps2_raw_t, vel) }, \ - { "cog", NULL, MAVLINK_TYPE_UINT16_T, 0, 30, offsetof(mavlink_gps2_raw_t, cog) }, \ - { "satellites_visible", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_gps2_raw_t, satellites_visible) }, \ - { "dgps_numch", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_gps2_raw_t, dgps_numch) }, \ - { "dgps_age", NULL, MAVLINK_TYPE_UINT32_T, 0, 20, offsetof(mavlink_gps2_raw_t, dgps_age) }, \ - { "yaw", NULL, MAVLINK_TYPE_UINT16_T, 0, 35, offsetof(mavlink_gps2_raw_t, yaw) }, \ - { "alt_ellipsoid", NULL, MAVLINK_TYPE_INT32_T, 0, 37, offsetof(mavlink_gps2_raw_t, alt_ellipsoid) }, \ - { "h_acc", NULL, MAVLINK_TYPE_UINT32_T, 0, 41, offsetof(mavlink_gps2_raw_t, h_acc) }, \ - { "v_acc", NULL, MAVLINK_TYPE_UINT32_T, 0, 45, offsetof(mavlink_gps2_raw_t, v_acc) }, \ - { "vel_acc", NULL, MAVLINK_TYPE_UINT32_T, 0, 49, offsetof(mavlink_gps2_raw_t, vel_acc) }, \ - { "hdg_acc", NULL, MAVLINK_TYPE_UINT32_T, 0, 53, offsetof(mavlink_gps2_raw_t, hdg_acc) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_GPS2_RAW { \ - "GPS2_RAW", \ - 18, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_gps2_raw_t, time_usec) }, \ - { "fix_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_gps2_raw_t, fix_type) }, \ - { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_gps2_raw_t, lat) }, \ - { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_gps2_raw_t, lon) }, \ - { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_gps2_raw_t, alt) }, \ - { "eph", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_gps2_raw_t, eph) }, \ - { "epv", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_gps2_raw_t, epv) }, \ - { "vel", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_gps2_raw_t, vel) }, \ - { "cog", NULL, MAVLINK_TYPE_UINT16_T, 0, 30, offsetof(mavlink_gps2_raw_t, cog) }, \ - { "satellites_visible", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_gps2_raw_t, satellites_visible) }, \ - { "dgps_numch", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_gps2_raw_t, dgps_numch) }, \ - { "dgps_age", NULL, MAVLINK_TYPE_UINT32_T, 0, 20, offsetof(mavlink_gps2_raw_t, dgps_age) }, \ - { "yaw", NULL, MAVLINK_TYPE_UINT16_T, 0, 35, offsetof(mavlink_gps2_raw_t, yaw) }, \ - { "alt_ellipsoid", NULL, MAVLINK_TYPE_INT32_T, 0, 37, offsetof(mavlink_gps2_raw_t, alt_ellipsoid) }, \ - { "h_acc", NULL, MAVLINK_TYPE_UINT32_T, 0, 41, offsetof(mavlink_gps2_raw_t, h_acc) }, \ - { "v_acc", NULL, MAVLINK_TYPE_UINT32_T, 0, 45, offsetof(mavlink_gps2_raw_t, v_acc) }, \ - { "vel_acc", NULL, MAVLINK_TYPE_UINT32_T, 0, 49, offsetof(mavlink_gps2_raw_t, vel_acc) }, \ - { "hdg_acc", NULL, MAVLINK_TYPE_UINT32_T, 0, 53, offsetof(mavlink_gps2_raw_t, hdg_acc) }, \ - } \ -} -#endif - -/** - * @brief Pack a gps2_raw message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @param fix_type GPS fix type. - * @param lat [degE7] Latitude (WGS84) - * @param lon [degE7] Longitude (WGS84) - * @param alt [mm] Altitude (MSL). Positive for up. - * @param eph GPS HDOP horizontal dilution of position (unitless * 100). If unknown, set to: UINT16_MAX - * @param epv GPS VDOP vertical dilution of position (unitless * 100). If unknown, set to: UINT16_MAX - * @param vel [cm/s] GPS ground speed. If unknown, set to: UINT16_MAX - * @param cog [cdeg] Course over ground (NOT heading, but direction of movement): 0.0..359.99 degrees. If unknown, set to: UINT16_MAX - * @param satellites_visible Number of satellites visible. If unknown, set to UINT8_MAX - * @param dgps_numch Number of DGPS satellites - * @param dgps_age [ms] Age of DGPS info - * @param yaw [cdeg] Yaw in earth frame from north. Use 0 if this GPS does not provide yaw. Use UINT16_MAX if this GPS is configured to provide yaw and is currently unable to provide it. Use 36000 for north. - * @param alt_ellipsoid [mm] Altitude (above WGS84, EGM96 ellipsoid). Positive for up. - * @param h_acc [mm] Position uncertainty. - * @param v_acc [mm] Altitude uncertainty. - * @param vel_acc [mm] Speed uncertainty. - * @param hdg_acc [degE5] Heading / track uncertainty - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_gps2_raw_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint64_t time_usec, uint8_t fix_type, int32_t lat, int32_t lon, int32_t alt, uint16_t eph, uint16_t epv, uint16_t vel, uint16_t cog, uint8_t satellites_visible, uint8_t dgps_numch, uint32_t dgps_age, uint16_t yaw, int32_t alt_ellipsoid, uint32_t h_acc, uint32_t v_acc, uint32_t vel_acc, uint32_t hdg_acc) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_GPS2_RAW_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_int32_t(buf, 8, lat); - _mav_put_int32_t(buf, 12, lon); - _mav_put_int32_t(buf, 16, alt); - _mav_put_uint32_t(buf, 20, dgps_age); - _mav_put_uint16_t(buf, 24, eph); - _mav_put_uint16_t(buf, 26, epv); - _mav_put_uint16_t(buf, 28, vel); - _mav_put_uint16_t(buf, 30, cog); - _mav_put_uint8_t(buf, 32, fix_type); - _mav_put_uint8_t(buf, 33, satellites_visible); - _mav_put_uint8_t(buf, 34, dgps_numch); - _mav_put_uint16_t(buf, 35, yaw); - _mav_put_int32_t(buf, 37, alt_ellipsoid); - _mav_put_uint32_t(buf, 41, h_acc); - _mav_put_uint32_t(buf, 45, v_acc); - _mav_put_uint32_t(buf, 49, vel_acc); - _mav_put_uint32_t(buf, 53, hdg_acc); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS2_RAW_LEN); -#else - mavlink_gps2_raw_t packet; - packet.time_usec = time_usec; - packet.lat = lat; - packet.lon = lon; - packet.alt = alt; - packet.dgps_age = dgps_age; - packet.eph = eph; - packet.epv = epv; - packet.vel = vel; - packet.cog = cog; - packet.fix_type = fix_type; - packet.satellites_visible = satellites_visible; - packet.dgps_numch = dgps_numch; - packet.yaw = yaw; - packet.alt_ellipsoid = alt_ellipsoid; - packet.h_acc = h_acc; - packet.v_acc = v_acc; - packet.vel_acc = vel_acc; - packet.hdg_acc = hdg_acc; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS2_RAW_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_GPS2_RAW; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS2_RAW_MIN_LEN, MAVLINK_MSG_ID_GPS2_RAW_LEN, MAVLINK_MSG_ID_GPS2_RAW_CRC); -} - -/** - * @brief Pack a gps2_raw message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @param fix_type GPS fix type. - * @param lat [degE7] Latitude (WGS84) - * @param lon [degE7] Longitude (WGS84) - * @param alt [mm] Altitude (MSL). Positive for up. - * @param eph GPS HDOP horizontal dilution of position (unitless * 100). If unknown, set to: UINT16_MAX - * @param epv GPS VDOP vertical dilution of position (unitless * 100). If unknown, set to: UINT16_MAX - * @param vel [cm/s] GPS ground speed. If unknown, set to: UINT16_MAX - * @param cog [cdeg] Course over ground (NOT heading, but direction of movement): 0.0..359.99 degrees. If unknown, set to: UINT16_MAX - * @param satellites_visible Number of satellites visible. If unknown, set to UINT8_MAX - * @param dgps_numch Number of DGPS satellites - * @param dgps_age [ms] Age of DGPS info - * @param yaw [cdeg] Yaw in earth frame from north. Use 0 if this GPS does not provide yaw. Use UINT16_MAX if this GPS is configured to provide yaw and is currently unable to provide it. Use 36000 for north. - * @param alt_ellipsoid [mm] Altitude (above WGS84, EGM96 ellipsoid). Positive for up. - * @param h_acc [mm] Position uncertainty. - * @param v_acc [mm] Altitude uncertainty. - * @param vel_acc [mm] Speed uncertainty. - * @param hdg_acc [degE5] Heading / track uncertainty - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_gps2_raw_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint64_t time_usec,uint8_t fix_type,int32_t lat,int32_t lon,int32_t alt,uint16_t eph,uint16_t epv,uint16_t vel,uint16_t cog,uint8_t satellites_visible,uint8_t dgps_numch,uint32_t dgps_age,uint16_t yaw,int32_t alt_ellipsoid,uint32_t h_acc,uint32_t v_acc,uint32_t vel_acc,uint32_t hdg_acc) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_GPS2_RAW_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_int32_t(buf, 8, lat); - _mav_put_int32_t(buf, 12, lon); - _mav_put_int32_t(buf, 16, alt); - _mav_put_uint32_t(buf, 20, dgps_age); - _mav_put_uint16_t(buf, 24, eph); - _mav_put_uint16_t(buf, 26, epv); - _mav_put_uint16_t(buf, 28, vel); - _mav_put_uint16_t(buf, 30, cog); - _mav_put_uint8_t(buf, 32, fix_type); - _mav_put_uint8_t(buf, 33, satellites_visible); - _mav_put_uint8_t(buf, 34, dgps_numch); - _mav_put_uint16_t(buf, 35, yaw); - _mav_put_int32_t(buf, 37, alt_ellipsoid); - _mav_put_uint32_t(buf, 41, h_acc); - _mav_put_uint32_t(buf, 45, v_acc); - _mav_put_uint32_t(buf, 49, vel_acc); - _mav_put_uint32_t(buf, 53, hdg_acc); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS2_RAW_LEN); -#else - mavlink_gps2_raw_t packet; - packet.time_usec = time_usec; - packet.lat = lat; - packet.lon = lon; - packet.alt = alt; - packet.dgps_age = dgps_age; - packet.eph = eph; - packet.epv = epv; - packet.vel = vel; - packet.cog = cog; - packet.fix_type = fix_type; - packet.satellites_visible = satellites_visible; - packet.dgps_numch = dgps_numch; - packet.yaw = yaw; - packet.alt_ellipsoid = alt_ellipsoid; - packet.h_acc = h_acc; - packet.v_acc = v_acc; - packet.vel_acc = vel_acc; - packet.hdg_acc = hdg_acc; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS2_RAW_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_GPS2_RAW; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GPS2_RAW_MIN_LEN, MAVLINK_MSG_ID_GPS2_RAW_LEN, MAVLINK_MSG_ID_GPS2_RAW_CRC); -} - -/** - * @brief Encode a gps2_raw struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param gps2_raw C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_gps2_raw_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gps2_raw_t* gps2_raw) -{ - return mavlink_msg_gps2_raw_pack(system_id, component_id, msg, gps2_raw->time_usec, gps2_raw->fix_type, gps2_raw->lat, gps2_raw->lon, gps2_raw->alt, gps2_raw->eph, gps2_raw->epv, gps2_raw->vel, gps2_raw->cog, gps2_raw->satellites_visible, gps2_raw->dgps_numch, gps2_raw->dgps_age, gps2_raw->yaw, gps2_raw->alt_ellipsoid, gps2_raw->h_acc, gps2_raw->v_acc, gps2_raw->vel_acc, gps2_raw->hdg_acc); -} - -/** - * @brief Encode a gps2_raw struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param gps2_raw C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_gps2_raw_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_gps2_raw_t* gps2_raw) -{ - return mavlink_msg_gps2_raw_pack_chan(system_id, component_id, chan, msg, gps2_raw->time_usec, gps2_raw->fix_type, gps2_raw->lat, gps2_raw->lon, gps2_raw->alt, gps2_raw->eph, gps2_raw->epv, gps2_raw->vel, gps2_raw->cog, gps2_raw->satellites_visible, gps2_raw->dgps_numch, gps2_raw->dgps_age, gps2_raw->yaw, gps2_raw->alt_ellipsoid, gps2_raw->h_acc, gps2_raw->v_acc, gps2_raw->vel_acc, gps2_raw->hdg_acc); -} - -/** - * @brief Send a gps2_raw message - * @param chan MAVLink channel to send the message - * - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @param fix_type GPS fix type. - * @param lat [degE7] Latitude (WGS84) - * @param lon [degE7] Longitude (WGS84) - * @param alt [mm] Altitude (MSL). Positive for up. - * @param eph GPS HDOP horizontal dilution of position (unitless * 100). If unknown, set to: UINT16_MAX - * @param epv GPS VDOP vertical dilution of position (unitless * 100). If unknown, set to: UINT16_MAX - * @param vel [cm/s] GPS ground speed. If unknown, set to: UINT16_MAX - * @param cog [cdeg] Course over ground (NOT heading, but direction of movement): 0.0..359.99 degrees. If unknown, set to: UINT16_MAX - * @param satellites_visible Number of satellites visible. If unknown, set to UINT8_MAX - * @param dgps_numch Number of DGPS satellites - * @param dgps_age [ms] Age of DGPS info - * @param yaw [cdeg] Yaw in earth frame from north. Use 0 if this GPS does not provide yaw. Use UINT16_MAX if this GPS is configured to provide yaw and is currently unable to provide it. Use 36000 for north. - * @param alt_ellipsoid [mm] Altitude (above WGS84, EGM96 ellipsoid). Positive for up. - * @param h_acc [mm] Position uncertainty. - * @param v_acc [mm] Altitude uncertainty. - * @param vel_acc [mm] Speed uncertainty. - * @param hdg_acc [degE5] Heading / track uncertainty - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_gps2_raw_send(mavlink_channel_t chan, uint64_t time_usec, uint8_t fix_type, int32_t lat, int32_t lon, int32_t alt, uint16_t eph, uint16_t epv, uint16_t vel, uint16_t cog, uint8_t satellites_visible, uint8_t dgps_numch, uint32_t dgps_age, uint16_t yaw, int32_t alt_ellipsoid, uint32_t h_acc, uint32_t v_acc, uint32_t vel_acc, uint32_t hdg_acc) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_GPS2_RAW_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_int32_t(buf, 8, lat); - _mav_put_int32_t(buf, 12, lon); - _mav_put_int32_t(buf, 16, alt); - _mav_put_uint32_t(buf, 20, dgps_age); - _mav_put_uint16_t(buf, 24, eph); - _mav_put_uint16_t(buf, 26, epv); - _mav_put_uint16_t(buf, 28, vel); - _mav_put_uint16_t(buf, 30, cog); - _mav_put_uint8_t(buf, 32, fix_type); - _mav_put_uint8_t(buf, 33, satellites_visible); - _mav_put_uint8_t(buf, 34, dgps_numch); - _mav_put_uint16_t(buf, 35, yaw); - _mav_put_int32_t(buf, 37, alt_ellipsoid); - _mav_put_uint32_t(buf, 41, h_acc); - _mav_put_uint32_t(buf, 45, v_acc); - _mav_put_uint32_t(buf, 49, vel_acc); - _mav_put_uint32_t(buf, 53, hdg_acc); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RAW, buf, MAVLINK_MSG_ID_GPS2_RAW_MIN_LEN, MAVLINK_MSG_ID_GPS2_RAW_LEN, MAVLINK_MSG_ID_GPS2_RAW_CRC); -#else - mavlink_gps2_raw_t packet; - packet.time_usec = time_usec; - packet.lat = lat; - packet.lon = lon; - packet.alt = alt; - packet.dgps_age = dgps_age; - packet.eph = eph; - packet.epv = epv; - packet.vel = vel; - packet.cog = cog; - packet.fix_type = fix_type; - packet.satellites_visible = satellites_visible; - packet.dgps_numch = dgps_numch; - packet.yaw = yaw; - packet.alt_ellipsoid = alt_ellipsoid; - packet.h_acc = h_acc; - packet.v_acc = v_acc; - packet.vel_acc = vel_acc; - packet.hdg_acc = hdg_acc; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RAW, (const char *)&packet, MAVLINK_MSG_ID_GPS2_RAW_MIN_LEN, MAVLINK_MSG_ID_GPS2_RAW_LEN, MAVLINK_MSG_ID_GPS2_RAW_CRC); -#endif -} - -/** - * @brief Send a gps2_raw message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_gps2_raw_send_struct(mavlink_channel_t chan, const mavlink_gps2_raw_t* gps2_raw) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_gps2_raw_send(chan, gps2_raw->time_usec, gps2_raw->fix_type, gps2_raw->lat, gps2_raw->lon, gps2_raw->alt, gps2_raw->eph, gps2_raw->epv, gps2_raw->vel, gps2_raw->cog, gps2_raw->satellites_visible, gps2_raw->dgps_numch, gps2_raw->dgps_age, gps2_raw->yaw, gps2_raw->alt_ellipsoid, gps2_raw->h_acc, gps2_raw->v_acc, gps2_raw->vel_acc, gps2_raw->hdg_acc); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RAW, (const char *)gps2_raw, MAVLINK_MSG_ID_GPS2_RAW_MIN_LEN, MAVLINK_MSG_ID_GPS2_RAW_LEN, MAVLINK_MSG_ID_GPS2_RAW_CRC); -#endif -} - -#if MAVLINK_MSG_ID_GPS2_RAW_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_gps2_raw_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, uint8_t fix_type, int32_t lat, int32_t lon, int32_t alt, uint16_t eph, uint16_t epv, uint16_t vel, uint16_t cog, uint8_t satellites_visible, uint8_t dgps_numch, uint32_t dgps_age, uint16_t yaw, int32_t alt_ellipsoid, uint32_t h_acc, uint32_t v_acc, uint32_t vel_acc, uint32_t hdg_acc) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_int32_t(buf, 8, lat); - _mav_put_int32_t(buf, 12, lon); - _mav_put_int32_t(buf, 16, alt); - _mav_put_uint32_t(buf, 20, dgps_age); - _mav_put_uint16_t(buf, 24, eph); - _mav_put_uint16_t(buf, 26, epv); - _mav_put_uint16_t(buf, 28, vel); - _mav_put_uint16_t(buf, 30, cog); - _mav_put_uint8_t(buf, 32, fix_type); - _mav_put_uint8_t(buf, 33, satellites_visible); - _mav_put_uint8_t(buf, 34, dgps_numch); - _mav_put_uint16_t(buf, 35, yaw); - _mav_put_int32_t(buf, 37, alt_ellipsoid); - _mav_put_uint32_t(buf, 41, h_acc); - _mav_put_uint32_t(buf, 45, v_acc); - _mav_put_uint32_t(buf, 49, vel_acc); - _mav_put_uint32_t(buf, 53, hdg_acc); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RAW, buf, MAVLINK_MSG_ID_GPS2_RAW_MIN_LEN, MAVLINK_MSG_ID_GPS2_RAW_LEN, MAVLINK_MSG_ID_GPS2_RAW_CRC); -#else - mavlink_gps2_raw_t *packet = (mavlink_gps2_raw_t *)msgbuf; - packet->time_usec = time_usec; - packet->lat = lat; - packet->lon = lon; - packet->alt = alt; - packet->dgps_age = dgps_age; - packet->eph = eph; - packet->epv = epv; - packet->vel = vel; - packet->cog = cog; - packet->fix_type = fix_type; - packet->satellites_visible = satellites_visible; - packet->dgps_numch = dgps_numch; - packet->yaw = yaw; - packet->alt_ellipsoid = alt_ellipsoid; - packet->h_acc = h_acc; - packet->v_acc = v_acc; - packet->vel_acc = vel_acc; - packet->hdg_acc = hdg_acc; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RAW, (const char *)packet, MAVLINK_MSG_ID_GPS2_RAW_MIN_LEN, MAVLINK_MSG_ID_GPS2_RAW_LEN, MAVLINK_MSG_ID_GPS2_RAW_CRC); -#endif -} -#endif - -#endif - -// MESSAGE GPS2_RAW UNPACKING - - -/** - * @brief Get field time_usec from gps2_raw message - * - * @return [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - */ -static inline uint64_t mavlink_msg_gps2_raw_get_time_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field fix_type from gps2_raw message - * - * @return GPS fix type. - */ -static inline uint8_t mavlink_msg_gps2_raw_get_fix_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 32); -} - -/** - * @brief Get field lat from gps2_raw message - * - * @return [degE7] Latitude (WGS84) - */ -static inline int32_t mavlink_msg_gps2_raw_get_lat(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 8); -} - -/** - * @brief Get field lon from gps2_raw message - * - * @return [degE7] Longitude (WGS84) - */ -static inline int32_t mavlink_msg_gps2_raw_get_lon(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 12); -} - -/** - * @brief Get field alt from gps2_raw message - * - * @return [mm] Altitude (MSL). Positive for up. - */ -static inline int32_t mavlink_msg_gps2_raw_get_alt(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 16); -} - -/** - * @brief Get field eph from gps2_raw message - * - * @return GPS HDOP horizontal dilution of position (unitless * 100). If unknown, set to: UINT16_MAX - */ -static inline uint16_t mavlink_msg_gps2_raw_get_eph(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 24); -} - -/** - * @brief Get field epv from gps2_raw message - * - * @return GPS VDOP vertical dilution of position (unitless * 100). If unknown, set to: UINT16_MAX - */ -static inline uint16_t mavlink_msg_gps2_raw_get_epv(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 26); -} - -/** - * @brief Get field vel from gps2_raw message - * - * @return [cm/s] GPS ground speed. If unknown, set to: UINT16_MAX - */ -static inline uint16_t mavlink_msg_gps2_raw_get_vel(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 28); -} - -/** - * @brief Get field cog from gps2_raw message - * - * @return [cdeg] Course over ground (NOT heading, but direction of movement): 0.0..359.99 degrees. If unknown, set to: UINT16_MAX - */ -static inline uint16_t mavlink_msg_gps2_raw_get_cog(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 30); -} - -/** - * @brief Get field satellites_visible from gps2_raw message - * - * @return Number of satellites visible. If unknown, set to UINT8_MAX - */ -static inline uint8_t mavlink_msg_gps2_raw_get_satellites_visible(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 33); -} - -/** - * @brief Get field dgps_numch from gps2_raw message - * - * @return Number of DGPS satellites - */ -static inline uint8_t mavlink_msg_gps2_raw_get_dgps_numch(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 34); -} - -/** - * @brief Get field dgps_age from gps2_raw message - * - * @return [ms] Age of DGPS info - */ -static inline uint32_t mavlink_msg_gps2_raw_get_dgps_age(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 20); -} - -/** - * @brief Get field yaw from gps2_raw message - * - * @return [cdeg] Yaw in earth frame from north. Use 0 if this GPS does not provide yaw. Use UINT16_MAX if this GPS is configured to provide yaw and is currently unable to provide it. Use 36000 for north. - */ -static inline uint16_t mavlink_msg_gps2_raw_get_yaw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 35); -} - -/** - * @brief Get field alt_ellipsoid from gps2_raw message - * - * @return [mm] Altitude (above WGS84, EGM96 ellipsoid). Positive for up. - */ -static inline int32_t mavlink_msg_gps2_raw_get_alt_ellipsoid(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 37); -} - -/** - * @brief Get field h_acc from gps2_raw message - * - * @return [mm] Position uncertainty. - */ -static inline uint32_t mavlink_msg_gps2_raw_get_h_acc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 41); -} - -/** - * @brief Get field v_acc from gps2_raw message - * - * @return [mm] Altitude uncertainty. - */ -static inline uint32_t mavlink_msg_gps2_raw_get_v_acc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 45); -} - -/** - * @brief Get field vel_acc from gps2_raw message - * - * @return [mm] Speed uncertainty. - */ -static inline uint32_t mavlink_msg_gps2_raw_get_vel_acc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 49); -} - -/** - * @brief Get field hdg_acc from gps2_raw message - * - * @return [degE5] Heading / track uncertainty - */ -static inline uint32_t mavlink_msg_gps2_raw_get_hdg_acc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 53); -} - -/** - * @brief Decode a gps2_raw message into a struct - * - * @param msg The message to decode - * @param gps2_raw C-struct to decode the message contents into - */ -static inline void mavlink_msg_gps2_raw_decode(const mavlink_message_t* msg, mavlink_gps2_raw_t* gps2_raw) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - gps2_raw->time_usec = mavlink_msg_gps2_raw_get_time_usec(msg); - gps2_raw->lat = mavlink_msg_gps2_raw_get_lat(msg); - gps2_raw->lon = mavlink_msg_gps2_raw_get_lon(msg); - gps2_raw->alt = mavlink_msg_gps2_raw_get_alt(msg); - gps2_raw->dgps_age = mavlink_msg_gps2_raw_get_dgps_age(msg); - gps2_raw->eph = mavlink_msg_gps2_raw_get_eph(msg); - gps2_raw->epv = mavlink_msg_gps2_raw_get_epv(msg); - gps2_raw->vel = mavlink_msg_gps2_raw_get_vel(msg); - gps2_raw->cog = mavlink_msg_gps2_raw_get_cog(msg); - gps2_raw->fix_type = mavlink_msg_gps2_raw_get_fix_type(msg); - gps2_raw->satellites_visible = mavlink_msg_gps2_raw_get_satellites_visible(msg); - gps2_raw->dgps_numch = mavlink_msg_gps2_raw_get_dgps_numch(msg); - gps2_raw->yaw = mavlink_msg_gps2_raw_get_yaw(msg); - gps2_raw->alt_ellipsoid = mavlink_msg_gps2_raw_get_alt_ellipsoid(msg); - gps2_raw->h_acc = mavlink_msg_gps2_raw_get_h_acc(msg); - gps2_raw->v_acc = mavlink_msg_gps2_raw_get_v_acc(msg); - gps2_raw->vel_acc = mavlink_msg_gps2_raw_get_vel_acc(msg); - gps2_raw->hdg_acc = mavlink_msg_gps2_raw_get_hdg_acc(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_GPS2_RAW_LEN? msg->len : MAVLINK_MSG_ID_GPS2_RAW_LEN; - memset(gps2_raw, 0, MAVLINK_MSG_ID_GPS2_RAW_LEN); - memcpy(gps2_raw, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_gps2_rtk.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_gps2_rtk.h deleted file mode 100644 index e546c70e..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_gps2_rtk.h +++ /dev/null @@ -1,513 +0,0 @@ -#pragma once -// MESSAGE GPS2_RTK PACKING - -#define MAVLINK_MSG_ID_GPS2_RTK 128 - - -typedef struct __mavlink_gps2_rtk_t { - uint32_t time_last_baseline_ms; /*< [ms] Time since boot of last baseline message received.*/ - uint32_t tow; /*< [ms] GPS Time of Week of last baseline*/ - int32_t baseline_a_mm; /*< [mm] Current baseline in ECEF x or NED north component.*/ - int32_t baseline_b_mm; /*< [mm] Current baseline in ECEF y or NED east component.*/ - int32_t baseline_c_mm; /*< [mm] Current baseline in ECEF z or NED down component.*/ - uint32_t accuracy; /*< Current estimate of baseline accuracy.*/ - int32_t iar_num_hypotheses; /*< Current number of integer ambiguity hypotheses.*/ - uint16_t wn; /*< GPS Week Number of last baseline*/ - uint8_t rtk_receiver_id; /*< Identification of connected RTK receiver.*/ - uint8_t rtk_health; /*< GPS-specific health report for RTK data.*/ - uint8_t rtk_rate; /*< [Hz] Rate of baseline messages being received by GPS*/ - uint8_t nsats; /*< Current number of sats used for RTK calculation.*/ - uint8_t baseline_coords_type; /*< Coordinate system of baseline*/ -} mavlink_gps2_rtk_t; - -#define MAVLINK_MSG_ID_GPS2_RTK_LEN 35 -#define MAVLINK_MSG_ID_GPS2_RTK_MIN_LEN 35 -#define MAVLINK_MSG_ID_128_LEN 35 -#define MAVLINK_MSG_ID_128_MIN_LEN 35 - -#define MAVLINK_MSG_ID_GPS2_RTK_CRC 226 -#define MAVLINK_MSG_ID_128_CRC 226 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_GPS2_RTK { \ - 128, \ - "GPS2_RTK", \ - 13, \ - { { "time_last_baseline_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_gps2_rtk_t, time_last_baseline_ms) }, \ - { "rtk_receiver_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_gps2_rtk_t, rtk_receiver_id) }, \ - { "wn", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_gps2_rtk_t, wn) }, \ - { "tow", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_gps2_rtk_t, tow) }, \ - { "rtk_health", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_gps2_rtk_t, rtk_health) }, \ - { "rtk_rate", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_gps2_rtk_t, rtk_rate) }, \ - { "nsats", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_gps2_rtk_t, nsats) }, \ - { "baseline_coords_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_gps2_rtk_t, baseline_coords_type) }, \ - { "baseline_a_mm", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_gps2_rtk_t, baseline_a_mm) }, \ - { "baseline_b_mm", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_gps2_rtk_t, baseline_b_mm) }, \ - { "baseline_c_mm", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_gps2_rtk_t, baseline_c_mm) }, \ - { "accuracy", NULL, MAVLINK_TYPE_UINT32_T, 0, 20, offsetof(mavlink_gps2_rtk_t, accuracy) }, \ - { "iar_num_hypotheses", NULL, MAVLINK_TYPE_INT32_T, 0, 24, offsetof(mavlink_gps2_rtk_t, iar_num_hypotheses) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_GPS2_RTK { \ - "GPS2_RTK", \ - 13, \ - { { "time_last_baseline_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_gps2_rtk_t, time_last_baseline_ms) }, \ - { "rtk_receiver_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_gps2_rtk_t, rtk_receiver_id) }, \ - { "wn", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_gps2_rtk_t, wn) }, \ - { "tow", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_gps2_rtk_t, tow) }, \ - { "rtk_health", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_gps2_rtk_t, rtk_health) }, \ - { "rtk_rate", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_gps2_rtk_t, rtk_rate) }, \ - { "nsats", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_gps2_rtk_t, nsats) }, \ - { "baseline_coords_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_gps2_rtk_t, baseline_coords_type) }, \ - { "baseline_a_mm", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_gps2_rtk_t, baseline_a_mm) }, \ - { "baseline_b_mm", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_gps2_rtk_t, baseline_b_mm) }, \ - { "baseline_c_mm", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_gps2_rtk_t, baseline_c_mm) }, \ - { "accuracy", NULL, MAVLINK_TYPE_UINT32_T, 0, 20, offsetof(mavlink_gps2_rtk_t, accuracy) }, \ - { "iar_num_hypotheses", NULL, MAVLINK_TYPE_INT32_T, 0, 24, offsetof(mavlink_gps2_rtk_t, iar_num_hypotheses) }, \ - } \ -} -#endif - -/** - * @brief Pack a gps2_rtk message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param time_last_baseline_ms [ms] Time since boot of last baseline message received. - * @param rtk_receiver_id Identification of connected RTK receiver. - * @param wn GPS Week Number of last baseline - * @param tow [ms] GPS Time of Week of last baseline - * @param rtk_health GPS-specific health report for RTK data. - * @param rtk_rate [Hz] Rate of baseline messages being received by GPS - * @param nsats Current number of sats used for RTK calculation. - * @param baseline_coords_type Coordinate system of baseline - * @param baseline_a_mm [mm] Current baseline in ECEF x or NED north component. - * @param baseline_b_mm [mm] Current baseline in ECEF y or NED east component. - * @param baseline_c_mm [mm] Current baseline in ECEF z or NED down component. - * @param accuracy Current estimate of baseline accuracy. - * @param iar_num_hypotheses Current number of integer ambiguity hypotheses. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_gps2_rtk_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint32_t time_last_baseline_ms, uint8_t rtk_receiver_id, uint16_t wn, uint32_t tow, uint8_t rtk_health, uint8_t rtk_rate, uint8_t nsats, uint8_t baseline_coords_type, int32_t baseline_a_mm, int32_t baseline_b_mm, int32_t baseline_c_mm, uint32_t accuracy, int32_t iar_num_hypotheses) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_GPS2_RTK_LEN]; - _mav_put_uint32_t(buf, 0, time_last_baseline_ms); - _mav_put_uint32_t(buf, 4, tow); - _mav_put_int32_t(buf, 8, baseline_a_mm); - _mav_put_int32_t(buf, 12, baseline_b_mm); - _mav_put_int32_t(buf, 16, baseline_c_mm); - _mav_put_uint32_t(buf, 20, accuracy); - _mav_put_int32_t(buf, 24, iar_num_hypotheses); - _mav_put_uint16_t(buf, 28, wn); - _mav_put_uint8_t(buf, 30, rtk_receiver_id); - _mav_put_uint8_t(buf, 31, rtk_health); - _mav_put_uint8_t(buf, 32, rtk_rate); - _mav_put_uint8_t(buf, 33, nsats); - _mav_put_uint8_t(buf, 34, baseline_coords_type); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS2_RTK_LEN); -#else - mavlink_gps2_rtk_t packet; - packet.time_last_baseline_ms = time_last_baseline_ms; - packet.tow = tow; - packet.baseline_a_mm = baseline_a_mm; - packet.baseline_b_mm = baseline_b_mm; - packet.baseline_c_mm = baseline_c_mm; - packet.accuracy = accuracy; - packet.iar_num_hypotheses = iar_num_hypotheses; - packet.wn = wn; - packet.rtk_receiver_id = rtk_receiver_id; - packet.rtk_health = rtk_health; - packet.rtk_rate = rtk_rate; - packet.nsats = nsats; - packet.baseline_coords_type = baseline_coords_type; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS2_RTK_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_GPS2_RTK; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS2_RTK_MIN_LEN, MAVLINK_MSG_ID_GPS2_RTK_LEN, MAVLINK_MSG_ID_GPS2_RTK_CRC); -} - -/** - * @brief Pack a gps2_rtk message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_last_baseline_ms [ms] Time since boot of last baseline message received. - * @param rtk_receiver_id Identification of connected RTK receiver. - * @param wn GPS Week Number of last baseline - * @param tow [ms] GPS Time of Week of last baseline - * @param rtk_health GPS-specific health report for RTK data. - * @param rtk_rate [Hz] Rate of baseline messages being received by GPS - * @param nsats Current number of sats used for RTK calculation. - * @param baseline_coords_type Coordinate system of baseline - * @param baseline_a_mm [mm] Current baseline in ECEF x or NED north component. - * @param baseline_b_mm [mm] Current baseline in ECEF y or NED east component. - * @param baseline_c_mm [mm] Current baseline in ECEF z or NED down component. - * @param accuracy Current estimate of baseline accuracy. - * @param iar_num_hypotheses Current number of integer ambiguity hypotheses. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_gps2_rtk_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint32_t time_last_baseline_ms,uint8_t rtk_receiver_id,uint16_t wn,uint32_t tow,uint8_t rtk_health,uint8_t rtk_rate,uint8_t nsats,uint8_t baseline_coords_type,int32_t baseline_a_mm,int32_t baseline_b_mm,int32_t baseline_c_mm,uint32_t accuracy,int32_t iar_num_hypotheses) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_GPS2_RTK_LEN]; - _mav_put_uint32_t(buf, 0, time_last_baseline_ms); - _mav_put_uint32_t(buf, 4, tow); - _mav_put_int32_t(buf, 8, baseline_a_mm); - _mav_put_int32_t(buf, 12, baseline_b_mm); - _mav_put_int32_t(buf, 16, baseline_c_mm); - _mav_put_uint32_t(buf, 20, accuracy); - _mav_put_int32_t(buf, 24, iar_num_hypotheses); - _mav_put_uint16_t(buf, 28, wn); - _mav_put_uint8_t(buf, 30, rtk_receiver_id); - _mav_put_uint8_t(buf, 31, rtk_health); - _mav_put_uint8_t(buf, 32, rtk_rate); - _mav_put_uint8_t(buf, 33, nsats); - _mav_put_uint8_t(buf, 34, baseline_coords_type); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS2_RTK_LEN); -#else - mavlink_gps2_rtk_t packet; - packet.time_last_baseline_ms = time_last_baseline_ms; - packet.tow = tow; - packet.baseline_a_mm = baseline_a_mm; - packet.baseline_b_mm = baseline_b_mm; - packet.baseline_c_mm = baseline_c_mm; - packet.accuracy = accuracy; - packet.iar_num_hypotheses = iar_num_hypotheses; - packet.wn = wn; - packet.rtk_receiver_id = rtk_receiver_id; - packet.rtk_health = rtk_health; - packet.rtk_rate = rtk_rate; - packet.nsats = nsats; - packet.baseline_coords_type = baseline_coords_type; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS2_RTK_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_GPS2_RTK; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GPS2_RTK_MIN_LEN, MAVLINK_MSG_ID_GPS2_RTK_LEN, MAVLINK_MSG_ID_GPS2_RTK_CRC); -} - -/** - * @brief Encode a gps2_rtk struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param gps2_rtk C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_gps2_rtk_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gps2_rtk_t* gps2_rtk) -{ - return mavlink_msg_gps2_rtk_pack(system_id, component_id, msg, gps2_rtk->time_last_baseline_ms, gps2_rtk->rtk_receiver_id, gps2_rtk->wn, gps2_rtk->tow, gps2_rtk->rtk_health, gps2_rtk->rtk_rate, gps2_rtk->nsats, gps2_rtk->baseline_coords_type, gps2_rtk->baseline_a_mm, gps2_rtk->baseline_b_mm, gps2_rtk->baseline_c_mm, gps2_rtk->accuracy, gps2_rtk->iar_num_hypotheses); -} - -/** - * @brief Encode a gps2_rtk struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param gps2_rtk C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_gps2_rtk_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_gps2_rtk_t* gps2_rtk) -{ - return mavlink_msg_gps2_rtk_pack_chan(system_id, component_id, chan, msg, gps2_rtk->time_last_baseline_ms, gps2_rtk->rtk_receiver_id, gps2_rtk->wn, gps2_rtk->tow, gps2_rtk->rtk_health, gps2_rtk->rtk_rate, gps2_rtk->nsats, gps2_rtk->baseline_coords_type, gps2_rtk->baseline_a_mm, gps2_rtk->baseline_b_mm, gps2_rtk->baseline_c_mm, gps2_rtk->accuracy, gps2_rtk->iar_num_hypotheses); -} - -/** - * @brief Send a gps2_rtk message - * @param chan MAVLink channel to send the message - * - * @param time_last_baseline_ms [ms] Time since boot of last baseline message received. - * @param rtk_receiver_id Identification of connected RTK receiver. - * @param wn GPS Week Number of last baseline - * @param tow [ms] GPS Time of Week of last baseline - * @param rtk_health GPS-specific health report for RTK data. - * @param rtk_rate [Hz] Rate of baseline messages being received by GPS - * @param nsats Current number of sats used for RTK calculation. - * @param baseline_coords_type Coordinate system of baseline - * @param baseline_a_mm [mm] Current baseline in ECEF x or NED north component. - * @param baseline_b_mm [mm] Current baseline in ECEF y or NED east component. - * @param baseline_c_mm [mm] Current baseline in ECEF z or NED down component. - * @param accuracy Current estimate of baseline accuracy. - * @param iar_num_hypotheses Current number of integer ambiguity hypotheses. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_gps2_rtk_send(mavlink_channel_t chan, uint32_t time_last_baseline_ms, uint8_t rtk_receiver_id, uint16_t wn, uint32_t tow, uint8_t rtk_health, uint8_t rtk_rate, uint8_t nsats, uint8_t baseline_coords_type, int32_t baseline_a_mm, int32_t baseline_b_mm, int32_t baseline_c_mm, uint32_t accuracy, int32_t iar_num_hypotheses) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_GPS2_RTK_LEN]; - _mav_put_uint32_t(buf, 0, time_last_baseline_ms); - _mav_put_uint32_t(buf, 4, tow); - _mav_put_int32_t(buf, 8, baseline_a_mm); - _mav_put_int32_t(buf, 12, baseline_b_mm); - _mav_put_int32_t(buf, 16, baseline_c_mm); - _mav_put_uint32_t(buf, 20, accuracy); - _mav_put_int32_t(buf, 24, iar_num_hypotheses); - _mav_put_uint16_t(buf, 28, wn); - _mav_put_uint8_t(buf, 30, rtk_receiver_id); - _mav_put_uint8_t(buf, 31, rtk_health); - _mav_put_uint8_t(buf, 32, rtk_rate); - _mav_put_uint8_t(buf, 33, nsats); - _mav_put_uint8_t(buf, 34, baseline_coords_type); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RTK, buf, MAVLINK_MSG_ID_GPS2_RTK_MIN_LEN, MAVLINK_MSG_ID_GPS2_RTK_LEN, MAVLINK_MSG_ID_GPS2_RTK_CRC); -#else - mavlink_gps2_rtk_t packet; - packet.time_last_baseline_ms = time_last_baseline_ms; - packet.tow = tow; - packet.baseline_a_mm = baseline_a_mm; - packet.baseline_b_mm = baseline_b_mm; - packet.baseline_c_mm = baseline_c_mm; - packet.accuracy = accuracy; - packet.iar_num_hypotheses = iar_num_hypotheses; - packet.wn = wn; - packet.rtk_receiver_id = rtk_receiver_id; - packet.rtk_health = rtk_health; - packet.rtk_rate = rtk_rate; - packet.nsats = nsats; - packet.baseline_coords_type = baseline_coords_type; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RTK, (const char *)&packet, MAVLINK_MSG_ID_GPS2_RTK_MIN_LEN, MAVLINK_MSG_ID_GPS2_RTK_LEN, MAVLINK_MSG_ID_GPS2_RTK_CRC); -#endif -} - -/** - * @brief Send a gps2_rtk message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_gps2_rtk_send_struct(mavlink_channel_t chan, const mavlink_gps2_rtk_t* gps2_rtk) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_gps2_rtk_send(chan, gps2_rtk->time_last_baseline_ms, gps2_rtk->rtk_receiver_id, gps2_rtk->wn, gps2_rtk->tow, gps2_rtk->rtk_health, gps2_rtk->rtk_rate, gps2_rtk->nsats, gps2_rtk->baseline_coords_type, gps2_rtk->baseline_a_mm, gps2_rtk->baseline_b_mm, gps2_rtk->baseline_c_mm, gps2_rtk->accuracy, gps2_rtk->iar_num_hypotheses); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RTK, (const char *)gps2_rtk, MAVLINK_MSG_ID_GPS2_RTK_MIN_LEN, MAVLINK_MSG_ID_GPS2_RTK_LEN, MAVLINK_MSG_ID_GPS2_RTK_CRC); -#endif -} - -#if MAVLINK_MSG_ID_GPS2_RTK_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_gps2_rtk_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_last_baseline_ms, uint8_t rtk_receiver_id, uint16_t wn, uint32_t tow, uint8_t rtk_health, uint8_t rtk_rate, uint8_t nsats, uint8_t baseline_coords_type, int32_t baseline_a_mm, int32_t baseline_b_mm, int32_t baseline_c_mm, uint32_t accuracy, int32_t iar_num_hypotheses) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, time_last_baseline_ms); - _mav_put_uint32_t(buf, 4, tow); - _mav_put_int32_t(buf, 8, baseline_a_mm); - _mav_put_int32_t(buf, 12, baseline_b_mm); - _mav_put_int32_t(buf, 16, baseline_c_mm); - _mav_put_uint32_t(buf, 20, accuracy); - _mav_put_int32_t(buf, 24, iar_num_hypotheses); - _mav_put_uint16_t(buf, 28, wn); - _mav_put_uint8_t(buf, 30, rtk_receiver_id); - _mav_put_uint8_t(buf, 31, rtk_health); - _mav_put_uint8_t(buf, 32, rtk_rate); - _mav_put_uint8_t(buf, 33, nsats); - _mav_put_uint8_t(buf, 34, baseline_coords_type); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RTK, buf, MAVLINK_MSG_ID_GPS2_RTK_MIN_LEN, MAVLINK_MSG_ID_GPS2_RTK_LEN, MAVLINK_MSG_ID_GPS2_RTK_CRC); -#else - mavlink_gps2_rtk_t *packet = (mavlink_gps2_rtk_t *)msgbuf; - packet->time_last_baseline_ms = time_last_baseline_ms; - packet->tow = tow; - packet->baseline_a_mm = baseline_a_mm; - packet->baseline_b_mm = baseline_b_mm; - packet->baseline_c_mm = baseline_c_mm; - packet->accuracy = accuracy; - packet->iar_num_hypotheses = iar_num_hypotheses; - packet->wn = wn; - packet->rtk_receiver_id = rtk_receiver_id; - packet->rtk_health = rtk_health; - packet->rtk_rate = rtk_rate; - packet->nsats = nsats; - packet->baseline_coords_type = baseline_coords_type; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RTK, (const char *)packet, MAVLINK_MSG_ID_GPS2_RTK_MIN_LEN, MAVLINK_MSG_ID_GPS2_RTK_LEN, MAVLINK_MSG_ID_GPS2_RTK_CRC); -#endif -} -#endif - -#endif - -// MESSAGE GPS2_RTK UNPACKING - - -/** - * @brief Get field time_last_baseline_ms from gps2_rtk message - * - * @return [ms] Time since boot of last baseline message received. - */ -static inline uint32_t mavlink_msg_gps2_rtk_get_time_last_baseline_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field rtk_receiver_id from gps2_rtk message - * - * @return Identification of connected RTK receiver. - */ -static inline uint8_t mavlink_msg_gps2_rtk_get_rtk_receiver_id(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 30); -} - -/** - * @brief Get field wn from gps2_rtk message - * - * @return GPS Week Number of last baseline - */ -static inline uint16_t mavlink_msg_gps2_rtk_get_wn(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 28); -} - -/** - * @brief Get field tow from gps2_rtk message - * - * @return [ms] GPS Time of Week of last baseline - */ -static inline uint32_t mavlink_msg_gps2_rtk_get_tow(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 4); -} - -/** - * @brief Get field rtk_health from gps2_rtk message - * - * @return GPS-specific health report for RTK data. - */ -static inline uint8_t mavlink_msg_gps2_rtk_get_rtk_health(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 31); -} - -/** - * @brief Get field rtk_rate from gps2_rtk message - * - * @return [Hz] Rate of baseline messages being received by GPS - */ -static inline uint8_t mavlink_msg_gps2_rtk_get_rtk_rate(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 32); -} - -/** - * @brief Get field nsats from gps2_rtk message - * - * @return Current number of sats used for RTK calculation. - */ -static inline uint8_t mavlink_msg_gps2_rtk_get_nsats(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 33); -} - -/** - * @brief Get field baseline_coords_type from gps2_rtk message - * - * @return Coordinate system of baseline - */ -static inline uint8_t mavlink_msg_gps2_rtk_get_baseline_coords_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 34); -} - -/** - * @brief Get field baseline_a_mm from gps2_rtk message - * - * @return [mm] Current baseline in ECEF x or NED north component. - */ -static inline int32_t mavlink_msg_gps2_rtk_get_baseline_a_mm(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 8); -} - -/** - * @brief Get field baseline_b_mm from gps2_rtk message - * - * @return [mm] Current baseline in ECEF y or NED east component. - */ -static inline int32_t mavlink_msg_gps2_rtk_get_baseline_b_mm(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 12); -} - -/** - * @brief Get field baseline_c_mm from gps2_rtk message - * - * @return [mm] Current baseline in ECEF z or NED down component. - */ -static inline int32_t mavlink_msg_gps2_rtk_get_baseline_c_mm(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 16); -} - -/** - * @brief Get field accuracy from gps2_rtk message - * - * @return Current estimate of baseline accuracy. - */ -static inline uint32_t mavlink_msg_gps2_rtk_get_accuracy(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 20); -} - -/** - * @brief Get field iar_num_hypotheses from gps2_rtk message - * - * @return Current number of integer ambiguity hypotheses. - */ -static inline int32_t mavlink_msg_gps2_rtk_get_iar_num_hypotheses(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 24); -} - -/** - * @brief Decode a gps2_rtk message into a struct - * - * @param msg The message to decode - * @param gps2_rtk C-struct to decode the message contents into - */ -static inline void mavlink_msg_gps2_rtk_decode(const mavlink_message_t* msg, mavlink_gps2_rtk_t* gps2_rtk) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - gps2_rtk->time_last_baseline_ms = mavlink_msg_gps2_rtk_get_time_last_baseline_ms(msg); - gps2_rtk->tow = mavlink_msg_gps2_rtk_get_tow(msg); - gps2_rtk->baseline_a_mm = mavlink_msg_gps2_rtk_get_baseline_a_mm(msg); - gps2_rtk->baseline_b_mm = mavlink_msg_gps2_rtk_get_baseline_b_mm(msg); - gps2_rtk->baseline_c_mm = mavlink_msg_gps2_rtk_get_baseline_c_mm(msg); - gps2_rtk->accuracy = mavlink_msg_gps2_rtk_get_accuracy(msg); - gps2_rtk->iar_num_hypotheses = mavlink_msg_gps2_rtk_get_iar_num_hypotheses(msg); - gps2_rtk->wn = mavlink_msg_gps2_rtk_get_wn(msg); - gps2_rtk->rtk_receiver_id = mavlink_msg_gps2_rtk_get_rtk_receiver_id(msg); - gps2_rtk->rtk_health = mavlink_msg_gps2_rtk_get_rtk_health(msg); - gps2_rtk->rtk_rate = mavlink_msg_gps2_rtk_get_rtk_rate(msg); - gps2_rtk->nsats = mavlink_msg_gps2_rtk_get_nsats(msg); - gps2_rtk->baseline_coords_type = mavlink_msg_gps2_rtk_get_baseline_coords_type(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_GPS2_RTK_LEN? msg->len : MAVLINK_MSG_ID_GPS2_RTK_LEN; - memset(gps2_rtk, 0, MAVLINK_MSG_ID_GPS2_RTK_LEN); - memcpy(gps2_rtk, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_gps_global_origin.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_gps_global_origin.h deleted file mode 100644 index c9a67774..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_gps_global_origin.h +++ /dev/null @@ -1,288 +0,0 @@ -#pragma once -// MESSAGE GPS_GLOBAL_ORIGIN PACKING - -#define MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN 49 - -MAVPACKED( -typedef struct __mavlink_gps_global_origin_t { - int32_t latitude; /*< [degE7] Latitude (WGS84)*/ - int32_t longitude; /*< [degE7] Longitude (WGS84)*/ - int32_t altitude; /*< [mm] Altitude (MSL). Positive for up.*/ - uint64_t time_usec; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/ -}) mavlink_gps_global_origin_t; - -#define MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN 20 -#define MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_MIN_LEN 12 -#define MAVLINK_MSG_ID_49_LEN 20 -#define MAVLINK_MSG_ID_49_MIN_LEN 12 - -#define MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_CRC 39 -#define MAVLINK_MSG_ID_49_CRC 39 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_GPS_GLOBAL_ORIGIN { \ - 49, \ - "GPS_GLOBAL_ORIGIN", \ - 4, \ - { { "latitude", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_gps_global_origin_t, latitude) }, \ - { "longitude", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_gps_global_origin_t, longitude) }, \ - { "altitude", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_gps_global_origin_t, altitude) }, \ - { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 12, offsetof(mavlink_gps_global_origin_t, time_usec) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_GPS_GLOBAL_ORIGIN { \ - "GPS_GLOBAL_ORIGIN", \ - 4, \ - { { "latitude", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_gps_global_origin_t, latitude) }, \ - { "longitude", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_gps_global_origin_t, longitude) }, \ - { "altitude", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_gps_global_origin_t, altitude) }, \ - { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 12, offsetof(mavlink_gps_global_origin_t, time_usec) }, \ - } \ -} -#endif - -/** - * @brief Pack a gps_global_origin message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param latitude [degE7] Latitude (WGS84) - * @param longitude [degE7] Longitude (WGS84) - * @param altitude [mm] Altitude (MSL). Positive for up. - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_gps_global_origin_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - int32_t latitude, int32_t longitude, int32_t altitude, uint64_t time_usec) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN]; - _mav_put_int32_t(buf, 0, latitude); - _mav_put_int32_t(buf, 4, longitude); - _mav_put_int32_t(buf, 8, altitude); - _mav_put_uint64_t(buf, 12, time_usec); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN); -#else - mavlink_gps_global_origin_t packet; - packet.latitude = latitude; - packet.longitude = longitude; - packet.altitude = altitude; - packet.time_usec = time_usec; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_MIN_LEN, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_CRC); -} - -/** - * @brief Pack a gps_global_origin message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param latitude [degE7] Latitude (WGS84) - * @param longitude [degE7] Longitude (WGS84) - * @param altitude [mm] Altitude (MSL). Positive for up. - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_gps_global_origin_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - int32_t latitude,int32_t longitude,int32_t altitude,uint64_t time_usec) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN]; - _mav_put_int32_t(buf, 0, latitude); - _mav_put_int32_t(buf, 4, longitude); - _mav_put_int32_t(buf, 8, altitude); - _mav_put_uint64_t(buf, 12, time_usec); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN); -#else - mavlink_gps_global_origin_t packet; - packet.latitude = latitude; - packet.longitude = longitude; - packet.altitude = altitude; - packet.time_usec = time_usec; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_MIN_LEN, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_CRC); -} - -/** - * @brief Encode a gps_global_origin struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param gps_global_origin C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_gps_global_origin_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gps_global_origin_t* gps_global_origin) -{ - return mavlink_msg_gps_global_origin_pack(system_id, component_id, msg, gps_global_origin->latitude, gps_global_origin->longitude, gps_global_origin->altitude, gps_global_origin->time_usec); -} - -/** - * @brief Encode a gps_global_origin struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param gps_global_origin C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_gps_global_origin_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_gps_global_origin_t* gps_global_origin) -{ - return mavlink_msg_gps_global_origin_pack_chan(system_id, component_id, chan, msg, gps_global_origin->latitude, gps_global_origin->longitude, gps_global_origin->altitude, gps_global_origin->time_usec); -} - -/** - * @brief Send a gps_global_origin message - * @param chan MAVLink channel to send the message - * - * @param latitude [degE7] Latitude (WGS84) - * @param longitude [degE7] Longitude (WGS84) - * @param altitude [mm] Altitude (MSL). Positive for up. - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_gps_global_origin_send(mavlink_channel_t chan, int32_t latitude, int32_t longitude, int32_t altitude, uint64_t time_usec) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN]; - _mav_put_int32_t(buf, 0, latitude); - _mav_put_int32_t(buf, 4, longitude); - _mav_put_int32_t(buf, 8, altitude); - _mav_put_uint64_t(buf, 12, time_usec); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN, buf, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_MIN_LEN, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_CRC); -#else - mavlink_gps_global_origin_t packet; - packet.latitude = latitude; - packet.longitude = longitude; - packet.altitude = altitude; - packet.time_usec = time_usec; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN, (const char *)&packet, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_MIN_LEN, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_CRC); -#endif -} - -/** - * @brief Send a gps_global_origin message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_gps_global_origin_send_struct(mavlink_channel_t chan, const mavlink_gps_global_origin_t* gps_global_origin) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_gps_global_origin_send(chan, gps_global_origin->latitude, gps_global_origin->longitude, gps_global_origin->altitude, gps_global_origin->time_usec); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN, (const char *)gps_global_origin, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_MIN_LEN, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_CRC); -#endif -} - -#if MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_gps_global_origin_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, int32_t latitude, int32_t longitude, int32_t altitude, uint64_t time_usec) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_int32_t(buf, 0, latitude); - _mav_put_int32_t(buf, 4, longitude); - _mav_put_int32_t(buf, 8, altitude); - _mav_put_uint64_t(buf, 12, time_usec); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN, buf, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_MIN_LEN, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_CRC); -#else - mavlink_gps_global_origin_t *packet = (mavlink_gps_global_origin_t *)msgbuf; - packet->latitude = latitude; - packet->longitude = longitude; - packet->altitude = altitude; - packet->time_usec = time_usec; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN, (const char *)packet, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_MIN_LEN, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_CRC); -#endif -} -#endif - -#endif - -// MESSAGE GPS_GLOBAL_ORIGIN UNPACKING - - -/** - * @brief Get field latitude from gps_global_origin message - * - * @return [degE7] Latitude (WGS84) - */ -static inline int32_t mavlink_msg_gps_global_origin_get_latitude(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 0); -} - -/** - * @brief Get field longitude from gps_global_origin message - * - * @return [degE7] Longitude (WGS84) - */ -static inline int32_t mavlink_msg_gps_global_origin_get_longitude(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 4); -} - -/** - * @brief Get field altitude from gps_global_origin message - * - * @return [mm] Altitude (MSL). Positive for up. - */ -static inline int32_t mavlink_msg_gps_global_origin_get_altitude(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 8); -} - -/** - * @brief Get field time_usec from gps_global_origin message - * - * @return [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - */ -static inline uint64_t mavlink_msg_gps_global_origin_get_time_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 12); -} - -/** - * @brief Decode a gps_global_origin message into a struct - * - * @param msg The message to decode - * @param gps_global_origin C-struct to decode the message contents into - */ -static inline void mavlink_msg_gps_global_origin_decode(const mavlink_message_t* msg, mavlink_gps_global_origin_t* gps_global_origin) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - gps_global_origin->latitude = mavlink_msg_gps_global_origin_get_latitude(msg); - gps_global_origin->longitude = mavlink_msg_gps_global_origin_get_longitude(msg); - gps_global_origin->altitude = mavlink_msg_gps_global_origin_get_altitude(msg); - gps_global_origin->time_usec = mavlink_msg_gps_global_origin_get_time_usec(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN? msg->len : MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN; - memset(gps_global_origin, 0, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN); - memcpy(gps_global_origin, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_gps_inject_data.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_gps_inject_data.h deleted file mode 100644 index 9b224267..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_gps_inject_data.h +++ /dev/null @@ -1,280 +0,0 @@ -#pragma once -// MESSAGE GPS_INJECT_DATA PACKING - -#define MAVLINK_MSG_ID_GPS_INJECT_DATA 123 - - -typedef struct __mavlink_gps_inject_data_t { - uint8_t target_system; /*< System ID*/ - uint8_t target_component; /*< Component ID*/ - uint8_t len; /*< [bytes] Data length*/ - uint8_t data[110]; /*< Raw data (110 is enough for 12 satellites of RTCMv2)*/ -} mavlink_gps_inject_data_t; - -#define MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN 113 -#define MAVLINK_MSG_ID_GPS_INJECT_DATA_MIN_LEN 113 -#define MAVLINK_MSG_ID_123_LEN 113 -#define MAVLINK_MSG_ID_123_MIN_LEN 113 - -#define MAVLINK_MSG_ID_GPS_INJECT_DATA_CRC 250 -#define MAVLINK_MSG_ID_123_CRC 250 - -#define MAVLINK_MSG_GPS_INJECT_DATA_FIELD_DATA_LEN 110 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_GPS_INJECT_DATA { \ - 123, \ - "GPS_INJECT_DATA", \ - 4, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_gps_inject_data_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_gps_inject_data_t, target_component) }, \ - { "len", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_gps_inject_data_t, len) }, \ - { "data", NULL, MAVLINK_TYPE_UINT8_T, 110, 3, offsetof(mavlink_gps_inject_data_t, data) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_GPS_INJECT_DATA { \ - "GPS_INJECT_DATA", \ - 4, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_gps_inject_data_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_gps_inject_data_t, target_component) }, \ - { "len", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_gps_inject_data_t, len) }, \ - { "data", NULL, MAVLINK_TYPE_UINT8_T, 110, 3, offsetof(mavlink_gps_inject_data_t, data) }, \ - } \ -} -#endif - -/** - * @brief Pack a gps_inject_data message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID - * @param target_component Component ID - * @param len [bytes] Data length - * @param data Raw data (110 is enough for 12 satellites of RTCMv2) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_gps_inject_data_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component, uint8_t len, const uint8_t *data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN]; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - _mav_put_uint8_t(buf, 2, len); - _mav_put_uint8_t_array(buf, 3, data, 110); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN); -#else - mavlink_gps_inject_data_t packet; - packet.target_system = target_system; - packet.target_component = target_component; - packet.len = len; - mav_array_memcpy(packet.data, data, sizeof(uint8_t)*110); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_GPS_INJECT_DATA; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS_INJECT_DATA_MIN_LEN, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN, MAVLINK_MSG_ID_GPS_INJECT_DATA_CRC); -} - -/** - * @brief Pack a gps_inject_data message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @param len [bytes] Data length - * @param data Raw data (110 is enough for 12 satellites of RTCMv2) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_gps_inject_data_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component,uint8_t len,const uint8_t *data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN]; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - _mav_put_uint8_t(buf, 2, len); - _mav_put_uint8_t_array(buf, 3, data, 110); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN); -#else - mavlink_gps_inject_data_t packet; - packet.target_system = target_system; - packet.target_component = target_component; - packet.len = len; - mav_array_memcpy(packet.data, data, sizeof(uint8_t)*110); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_GPS_INJECT_DATA; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GPS_INJECT_DATA_MIN_LEN, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN, MAVLINK_MSG_ID_GPS_INJECT_DATA_CRC); -} - -/** - * @brief Encode a gps_inject_data struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param gps_inject_data C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_gps_inject_data_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gps_inject_data_t* gps_inject_data) -{ - return mavlink_msg_gps_inject_data_pack(system_id, component_id, msg, gps_inject_data->target_system, gps_inject_data->target_component, gps_inject_data->len, gps_inject_data->data); -} - -/** - * @brief Encode a gps_inject_data struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param gps_inject_data C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_gps_inject_data_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_gps_inject_data_t* gps_inject_data) -{ - return mavlink_msg_gps_inject_data_pack_chan(system_id, component_id, chan, msg, gps_inject_data->target_system, gps_inject_data->target_component, gps_inject_data->len, gps_inject_data->data); -} - -/** - * @brief Send a gps_inject_data message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param target_component Component ID - * @param len [bytes] Data length - * @param data Raw data (110 is enough for 12 satellites of RTCMv2) - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_gps_inject_data_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t len, const uint8_t *data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN]; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - _mav_put_uint8_t(buf, 2, len); - _mav_put_uint8_t_array(buf, 3, data, 110); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_INJECT_DATA, buf, MAVLINK_MSG_ID_GPS_INJECT_DATA_MIN_LEN, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN, MAVLINK_MSG_ID_GPS_INJECT_DATA_CRC); -#else - mavlink_gps_inject_data_t packet; - packet.target_system = target_system; - packet.target_component = target_component; - packet.len = len; - mav_array_memcpy(packet.data, data, sizeof(uint8_t)*110); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_INJECT_DATA, (const char *)&packet, MAVLINK_MSG_ID_GPS_INJECT_DATA_MIN_LEN, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN, MAVLINK_MSG_ID_GPS_INJECT_DATA_CRC); -#endif -} - -/** - * @brief Send a gps_inject_data message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_gps_inject_data_send_struct(mavlink_channel_t chan, const mavlink_gps_inject_data_t* gps_inject_data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_gps_inject_data_send(chan, gps_inject_data->target_system, gps_inject_data->target_component, gps_inject_data->len, gps_inject_data->data); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_INJECT_DATA, (const char *)gps_inject_data, MAVLINK_MSG_ID_GPS_INJECT_DATA_MIN_LEN, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN, MAVLINK_MSG_ID_GPS_INJECT_DATA_CRC); -#endif -} - -#if MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_gps_inject_data_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t len, const uint8_t *data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - _mav_put_uint8_t(buf, 2, len); - _mav_put_uint8_t_array(buf, 3, data, 110); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_INJECT_DATA, buf, MAVLINK_MSG_ID_GPS_INJECT_DATA_MIN_LEN, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN, MAVLINK_MSG_ID_GPS_INJECT_DATA_CRC); -#else - mavlink_gps_inject_data_t *packet = (mavlink_gps_inject_data_t *)msgbuf; - packet->target_system = target_system; - packet->target_component = target_component; - packet->len = len; - mav_array_memcpy(packet->data, data, sizeof(uint8_t)*110); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_INJECT_DATA, (const char *)packet, MAVLINK_MSG_ID_GPS_INJECT_DATA_MIN_LEN, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN, MAVLINK_MSG_ID_GPS_INJECT_DATA_CRC); -#endif -} -#endif - -#endif - -// MESSAGE GPS_INJECT_DATA UNPACKING - - -/** - * @brief Get field target_system from gps_inject_data message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_gps_inject_data_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 0); -} - -/** - * @brief Get field target_component from gps_inject_data message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_gps_inject_data_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 1); -} - -/** - * @brief Get field len from gps_inject_data message - * - * @return [bytes] Data length - */ -static inline uint8_t mavlink_msg_gps_inject_data_get_len(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 2); -} - -/** - * @brief Get field data from gps_inject_data message - * - * @return Raw data (110 is enough for 12 satellites of RTCMv2) - */ -static inline uint16_t mavlink_msg_gps_inject_data_get_data(const mavlink_message_t* msg, uint8_t *data) -{ - return _MAV_RETURN_uint8_t_array(msg, data, 110, 3); -} - -/** - * @brief Decode a gps_inject_data message into a struct - * - * @param msg The message to decode - * @param gps_inject_data C-struct to decode the message contents into - */ -static inline void mavlink_msg_gps_inject_data_decode(const mavlink_message_t* msg, mavlink_gps_inject_data_t* gps_inject_data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - gps_inject_data->target_system = mavlink_msg_gps_inject_data_get_target_system(msg); - gps_inject_data->target_component = mavlink_msg_gps_inject_data_get_target_component(msg); - gps_inject_data->len = mavlink_msg_gps_inject_data_get_len(msg); - mavlink_msg_gps_inject_data_get_data(msg, gps_inject_data->data); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN? msg->len : MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN; - memset(gps_inject_data, 0, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN); - memcpy(gps_inject_data, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_gps_input.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_gps_input.h deleted file mode 100644 index 6e920f21..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_gps_input.h +++ /dev/null @@ -1,663 +0,0 @@ -#pragma once -// MESSAGE GPS_INPUT PACKING - -#define MAVLINK_MSG_ID_GPS_INPUT 232 - -MAVPACKED( -typedef struct __mavlink_gps_input_t { - uint64_t time_usec; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/ - uint32_t time_week_ms; /*< [ms] GPS time (from start of GPS week)*/ - int32_t lat; /*< [degE7] Latitude (WGS84)*/ - int32_t lon; /*< [degE7] Longitude (WGS84)*/ - float alt; /*< [m] Altitude (MSL). Positive for up.*/ - float hdop; /*< GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX*/ - float vdop; /*< GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX*/ - float vn; /*< [m/s] GPS velocity in north direction in earth-fixed NED frame*/ - float ve; /*< [m/s] GPS velocity in east direction in earth-fixed NED frame*/ - float vd; /*< [m/s] GPS velocity in down direction in earth-fixed NED frame*/ - float speed_accuracy; /*< [m/s] GPS speed accuracy*/ - float horiz_accuracy; /*< [m] GPS horizontal accuracy*/ - float vert_accuracy; /*< [m] GPS vertical accuracy*/ - uint16_t ignore_flags; /*< Bitmap indicating which GPS input flags fields to ignore. All other fields must be provided.*/ - uint16_t time_week; /*< GPS week number*/ - uint8_t gps_id; /*< ID of the GPS for multiple GPS inputs*/ - uint8_t fix_type; /*< 0-1: no fix, 2: 2D fix, 3: 3D fix. 4: 3D with DGPS. 5: 3D with RTK*/ - uint8_t satellites_visible; /*< Number of satellites visible.*/ - uint16_t yaw; /*< [cdeg] Yaw of vehicle relative to Earth's North, zero means not available, use 36000 for north*/ -}) mavlink_gps_input_t; - -#define MAVLINK_MSG_ID_GPS_INPUT_LEN 65 -#define MAVLINK_MSG_ID_GPS_INPUT_MIN_LEN 63 -#define MAVLINK_MSG_ID_232_LEN 65 -#define MAVLINK_MSG_ID_232_MIN_LEN 63 - -#define MAVLINK_MSG_ID_GPS_INPUT_CRC 151 -#define MAVLINK_MSG_ID_232_CRC 151 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_GPS_INPUT { \ - 232, \ - "GPS_INPUT", \ - 19, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_gps_input_t, time_usec) }, \ - { "gps_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 60, offsetof(mavlink_gps_input_t, gps_id) }, \ - { "ignore_flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 56, offsetof(mavlink_gps_input_t, ignore_flags) }, \ - { "time_week_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_gps_input_t, time_week_ms) }, \ - { "time_week", NULL, MAVLINK_TYPE_UINT16_T, 0, 58, offsetof(mavlink_gps_input_t, time_week) }, \ - { "fix_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 61, offsetof(mavlink_gps_input_t, fix_type) }, \ - { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_gps_input_t, lat) }, \ - { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_gps_input_t, lon) }, \ - { "alt", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_gps_input_t, alt) }, \ - { "hdop", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_gps_input_t, hdop) }, \ - { "vdop", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_gps_input_t, vdop) }, \ - { "vn", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_gps_input_t, vn) }, \ - { "ve", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_gps_input_t, ve) }, \ - { "vd", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_gps_input_t, vd) }, \ - { "speed_accuracy", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_gps_input_t, speed_accuracy) }, \ - { "horiz_accuracy", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_gps_input_t, horiz_accuracy) }, \ - { "vert_accuracy", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_gps_input_t, vert_accuracy) }, \ - { "satellites_visible", NULL, MAVLINK_TYPE_UINT8_T, 0, 62, offsetof(mavlink_gps_input_t, satellites_visible) }, \ - { "yaw", NULL, MAVLINK_TYPE_UINT16_T, 0, 63, offsetof(mavlink_gps_input_t, yaw) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_GPS_INPUT { \ - "GPS_INPUT", \ - 19, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_gps_input_t, time_usec) }, \ - { "gps_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 60, offsetof(mavlink_gps_input_t, gps_id) }, \ - { "ignore_flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 56, offsetof(mavlink_gps_input_t, ignore_flags) }, \ - { "time_week_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_gps_input_t, time_week_ms) }, \ - { "time_week", NULL, MAVLINK_TYPE_UINT16_T, 0, 58, offsetof(mavlink_gps_input_t, time_week) }, \ - { "fix_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 61, offsetof(mavlink_gps_input_t, fix_type) }, \ - { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_gps_input_t, lat) }, \ - { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_gps_input_t, lon) }, \ - { "alt", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_gps_input_t, alt) }, \ - { "hdop", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_gps_input_t, hdop) }, \ - { "vdop", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_gps_input_t, vdop) }, \ - { "vn", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_gps_input_t, vn) }, \ - { "ve", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_gps_input_t, ve) }, \ - { "vd", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_gps_input_t, vd) }, \ - { "speed_accuracy", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_gps_input_t, speed_accuracy) }, \ - { "horiz_accuracy", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_gps_input_t, horiz_accuracy) }, \ - { "vert_accuracy", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_gps_input_t, vert_accuracy) }, \ - { "satellites_visible", NULL, MAVLINK_TYPE_UINT8_T, 0, 62, offsetof(mavlink_gps_input_t, satellites_visible) }, \ - { "yaw", NULL, MAVLINK_TYPE_UINT16_T, 0, 63, offsetof(mavlink_gps_input_t, yaw) }, \ - } \ -} -#endif - -/** - * @brief Pack a gps_input message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @param gps_id ID of the GPS for multiple GPS inputs - * @param ignore_flags Bitmap indicating which GPS input flags fields to ignore. All other fields must be provided. - * @param time_week_ms [ms] GPS time (from start of GPS week) - * @param time_week GPS week number - * @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix. 4: 3D with DGPS. 5: 3D with RTK - * @param lat [degE7] Latitude (WGS84) - * @param lon [degE7] Longitude (WGS84) - * @param alt [m] Altitude (MSL). Positive for up. - * @param hdop GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX - * @param vdop GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX - * @param vn [m/s] GPS velocity in north direction in earth-fixed NED frame - * @param ve [m/s] GPS velocity in east direction in earth-fixed NED frame - * @param vd [m/s] GPS velocity in down direction in earth-fixed NED frame - * @param speed_accuracy [m/s] GPS speed accuracy - * @param horiz_accuracy [m] GPS horizontal accuracy - * @param vert_accuracy [m] GPS vertical accuracy - * @param satellites_visible Number of satellites visible. - * @param yaw [cdeg] Yaw of vehicle relative to Earth's North, zero means not available, use 36000 for north - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_gps_input_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint64_t time_usec, uint8_t gps_id, uint16_t ignore_flags, uint32_t time_week_ms, uint16_t time_week, uint8_t fix_type, int32_t lat, int32_t lon, float alt, float hdop, float vdop, float vn, float ve, float vd, float speed_accuracy, float horiz_accuracy, float vert_accuracy, uint8_t satellites_visible, uint16_t yaw) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_GPS_INPUT_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint32_t(buf, 8, time_week_ms); - _mav_put_int32_t(buf, 12, lat); - _mav_put_int32_t(buf, 16, lon); - _mav_put_float(buf, 20, alt); - _mav_put_float(buf, 24, hdop); - _mav_put_float(buf, 28, vdop); - _mav_put_float(buf, 32, vn); - _mav_put_float(buf, 36, ve); - _mav_put_float(buf, 40, vd); - _mav_put_float(buf, 44, speed_accuracy); - _mav_put_float(buf, 48, horiz_accuracy); - _mav_put_float(buf, 52, vert_accuracy); - _mav_put_uint16_t(buf, 56, ignore_flags); - _mav_put_uint16_t(buf, 58, time_week); - _mav_put_uint8_t(buf, 60, gps_id); - _mav_put_uint8_t(buf, 61, fix_type); - _mav_put_uint8_t(buf, 62, satellites_visible); - _mav_put_uint16_t(buf, 63, yaw); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS_INPUT_LEN); -#else - mavlink_gps_input_t packet; - packet.time_usec = time_usec; - packet.time_week_ms = time_week_ms; - packet.lat = lat; - packet.lon = lon; - packet.alt = alt; - packet.hdop = hdop; - packet.vdop = vdop; - packet.vn = vn; - packet.ve = ve; - packet.vd = vd; - packet.speed_accuracy = speed_accuracy; - packet.horiz_accuracy = horiz_accuracy; - packet.vert_accuracy = vert_accuracy; - packet.ignore_flags = ignore_flags; - packet.time_week = time_week; - packet.gps_id = gps_id; - packet.fix_type = fix_type; - packet.satellites_visible = satellites_visible; - packet.yaw = yaw; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS_INPUT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_GPS_INPUT; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS_INPUT_MIN_LEN, MAVLINK_MSG_ID_GPS_INPUT_LEN, MAVLINK_MSG_ID_GPS_INPUT_CRC); -} - -/** - * @brief Pack a gps_input message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @param gps_id ID of the GPS for multiple GPS inputs - * @param ignore_flags Bitmap indicating which GPS input flags fields to ignore. All other fields must be provided. - * @param time_week_ms [ms] GPS time (from start of GPS week) - * @param time_week GPS week number - * @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix. 4: 3D with DGPS. 5: 3D with RTK - * @param lat [degE7] Latitude (WGS84) - * @param lon [degE7] Longitude (WGS84) - * @param alt [m] Altitude (MSL). Positive for up. - * @param hdop GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX - * @param vdop GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX - * @param vn [m/s] GPS velocity in north direction in earth-fixed NED frame - * @param ve [m/s] GPS velocity in east direction in earth-fixed NED frame - * @param vd [m/s] GPS velocity in down direction in earth-fixed NED frame - * @param speed_accuracy [m/s] GPS speed accuracy - * @param horiz_accuracy [m] GPS horizontal accuracy - * @param vert_accuracy [m] GPS vertical accuracy - * @param satellites_visible Number of satellites visible. - * @param yaw [cdeg] Yaw of vehicle relative to Earth's North, zero means not available, use 36000 for north - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_gps_input_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint64_t time_usec,uint8_t gps_id,uint16_t ignore_flags,uint32_t time_week_ms,uint16_t time_week,uint8_t fix_type,int32_t lat,int32_t lon,float alt,float hdop,float vdop,float vn,float ve,float vd,float speed_accuracy,float horiz_accuracy,float vert_accuracy,uint8_t satellites_visible,uint16_t yaw) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_GPS_INPUT_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint32_t(buf, 8, time_week_ms); - _mav_put_int32_t(buf, 12, lat); - _mav_put_int32_t(buf, 16, lon); - _mav_put_float(buf, 20, alt); - _mav_put_float(buf, 24, hdop); - _mav_put_float(buf, 28, vdop); - _mav_put_float(buf, 32, vn); - _mav_put_float(buf, 36, ve); - _mav_put_float(buf, 40, vd); - _mav_put_float(buf, 44, speed_accuracy); - _mav_put_float(buf, 48, horiz_accuracy); - _mav_put_float(buf, 52, vert_accuracy); - _mav_put_uint16_t(buf, 56, ignore_flags); - _mav_put_uint16_t(buf, 58, time_week); - _mav_put_uint8_t(buf, 60, gps_id); - _mav_put_uint8_t(buf, 61, fix_type); - _mav_put_uint8_t(buf, 62, satellites_visible); - _mav_put_uint16_t(buf, 63, yaw); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS_INPUT_LEN); -#else - mavlink_gps_input_t packet; - packet.time_usec = time_usec; - packet.time_week_ms = time_week_ms; - packet.lat = lat; - packet.lon = lon; - packet.alt = alt; - packet.hdop = hdop; - packet.vdop = vdop; - packet.vn = vn; - packet.ve = ve; - packet.vd = vd; - packet.speed_accuracy = speed_accuracy; - packet.horiz_accuracy = horiz_accuracy; - packet.vert_accuracy = vert_accuracy; - packet.ignore_flags = ignore_flags; - packet.time_week = time_week; - packet.gps_id = gps_id; - packet.fix_type = fix_type; - packet.satellites_visible = satellites_visible; - packet.yaw = yaw; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS_INPUT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_GPS_INPUT; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GPS_INPUT_MIN_LEN, MAVLINK_MSG_ID_GPS_INPUT_LEN, MAVLINK_MSG_ID_GPS_INPUT_CRC); -} - -/** - * @brief Encode a gps_input struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param gps_input C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_gps_input_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gps_input_t* gps_input) -{ - return mavlink_msg_gps_input_pack(system_id, component_id, msg, gps_input->time_usec, gps_input->gps_id, gps_input->ignore_flags, gps_input->time_week_ms, gps_input->time_week, gps_input->fix_type, gps_input->lat, gps_input->lon, gps_input->alt, gps_input->hdop, gps_input->vdop, gps_input->vn, gps_input->ve, gps_input->vd, gps_input->speed_accuracy, gps_input->horiz_accuracy, gps_input->vert_accuracy, gps_input->satellites_visible, gps_input->yaw); -} - -/** - * @brief Encode a gps_input struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param gps_input C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_gps_input_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_gps_input_t* gps_input) -{ - return mavlink_msg_gps_input_pack_chan(system_id, component_id, chan, msg, gps_input->time_usec, gps_input->gps_id, gps_input->ignore_flags, gps_input->time_week_ms, gps_input->time_week, gps_input->fix_type, gps_input->lat, gps_input->lon, gps_input->alt, gps_input->hdop, gps_input->vdop, gps_input->vn, gps_input->ve, gps_input->vd, gps_input->speed_accuracy, gps_input->horiz_accuracy, gps_input->vert_accuracy, gps_input->satellites_visible, gps_input->yaw); -} - -/** - * @brief Send a gps_input message - * @param chan MAVLink channel to send the message - * - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @param gps_id ID of the GPS for multiple GPS inputs - * @param ignore_flags Bitmap indicating which GPS input flags fields to ignore. All other fields must be provided. - * @param time_week_ms [ms] GPS time (from start of GPS week) - * @param time_week GPS week number - * @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix. 4: 3D with DGPS. 5: 3D with RTK - * @param lat [degE7] Latitude (WGS84) - * @param lon [degE7] Longitude (WGS84) - * @param alt [m] Altitude (MSL). Positive for up. - * @param hdop GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX - * @param vdop GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX - * @param vn [m/s] GPS velocity in north direction in earth-fixed NED frame - * @param ve [m/s] GPS velocity in east direction in earth-fixed NED frame - * @param vd [m/s] GPS velocity in down direction in earth-fixed NED frame - * @param speed_accuracy [m/s] GPS speed accuracy - * @param horiz_accuracy [m] GPS horizontal accuracy - * @param vert_accuracy [m] GPS vertical accuracy - * @param satellites_visible Number of satellites visible. - * @param yaw [cdeg] Yaw of vehicle relative to Earth's North, zero means not available, use 36000 for north - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_gps_input_send(mavlink_channel_t chan, uint64_t time_usec, uint8_t gps_id, uint16_t ignore_flags, uint32_t time_week_ms, uint16_t time_week, uint8_t fix_type, int32_t lat, int32_t lon, float alt, float hdop, float vdop, float vn, float ve, float vd, float speed_accuracy, float horiz_accuracy, float vert_accuracy, uint8_t satellites_visible, uint16_t yaw) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_GPS_INPUT_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint32_t(buf, 8, time_week_ms); - _mav_put_int32_t(buf, 12, lat); - _mav_put_int32_t(buf, 16, lon); - _mav_put_float(buf, 20, alt); - _mav_put_float(buf, 24, hdop); - _mav_put_float(buf, 28, vdop); - _mav_put_float(buf, 32, vn); - _mav_put_float(buf, 36, ve); - _mav_put_float(buf, 40, vd); - _mav_put_float(buf, 44, speed_accuracy); - _mav_put_float(buf, 48, horiz_accuracy); - _mav_put_float(buf, 52, vert_accuracy); - _mav_put_uint16_t(buf, 56, ignore_flags); - _mav_put_uint16_t(buf, 58, time_week); - _mav_put_uint8_t(buf, 60, gps_id); - _mav_put_uint8_t(buf, 61, fix_type); - _mav_put_uint8_t(buf, 62, satellites_visible); - _mav_put_uint16_t(buf, 63, yaw); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_INPUT, buf, MAVLINK_MSG_ID_GPS_INPUT_MIN_LEN, MAVLINK_MSG_ID_GPS_INPUT_LEN, MAVLINK_MSG_ID_GPS_INPUT_CRC); -#else - mavlink_gps_input_t packet; - packet.time_usec = time_usec; - packet.time_week_ms = time_week_ms; - packet.lat = lat; - packet.lon = lon; - packet.alt = alt; - packet.hdop = hdop; - packet.vdop = vdop; - packet.vn = vn; - packet.ve = ve; - packet.vd = vd; - packet.speed_accuracy = speed_accuracy; - packet.horiz_accuracy = horiz_accuracy; - packet.vert_accuracy = vert_accuracy; - packet.ignore_flags = ignore_flags; - packet.time_week = time_week; - packet.gps_id = gps_id; - packet.fix_type = fix_type; - packet.satellites_visible = satellites_visible; - packet.yaw = yaw; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_INPUT, (const char *)&packet, MAVLINK_MSG_ID_GPS_INPUT_MIN_LEN, MAVLINK_MSG_ID_GPS_INPUT_LEN, MAVLINK_MSG_ID_GPS_INPUT_CRC); -#endif -} - -/** - * @brief Send a gps_input message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_gps_input_send_struct(mavlink_channel_t chan, const mavlink_gps_input_t* gps_input) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_gps_input_send(chan, gps_input->time_usec, gps_input->gps_id, gps_input->ignore_flags, gps_input->time_week_ms, gps_input->time_week, gps_input->fix_type, gps_input->lat, gps_input->lon, gps_input->alt, gps_input->hdop, gps_input->vdop, gps_input->vn, gps_input->ve, gps_input->vd, gps_input->speed_accuracy, gps_input->horiz_accuracy, gps_input->vert_accuracy, gps_input->satellites_visible, gps_input->yaw); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_INPUT, (const char *)gps_input, MAVLINK_MSG_ID_GPS_INPUT_MIN_LEN, MAVLINK_MSG_ID_GPS_INPUT_LEN, MAVLINK_MSG_ID_GPS_INPUT_CRC); -#endif -} - -#if MAVLINK_MSG_ID_GPS_INPUT_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_gps_input_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, uint8_t gps_id, uint16_t ignore_flags, uint32_t time_week_ms, uint16_t time_week, uint8_t fix_type, int32_t lat, int32_t lon, float alt, float hdop, float vdop, float vn, float ve, float vd, float speed_accuracy, float horiz_accuracy, float vert_accuracy, uint8_t satellites_visible, uint16_t yaw) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint32_t(buf, 8, time_week_ms); - _mav_put_int32_t(buf, 12, lat); - _mav_put_int32_t(buf, 16, lon); - _mav_put_float(buf, 20, alt); - _mav_put_float(buf, 24, hdop); - _mav_put_float(buf, 28, vdop); - _mav_put_float(buf, 32, vn); - _mav_put_float(buf, 36, ve); - _mav_put_float(buf, 40, vd); - _mav_put_float(buf, 44, speed_accuracy); - _mav_put_float(buf, 48, horiz_accuracy); - _mav_put_float(buf, 52, vert_accuracy); - _mav_put_uint16_t(buf, 56, ignore_flags); - _mav_put_uint16_t(buf, 58, time_week); - _mav_put_uint8_t(buf, 60, gps_id); - _mav_put_uint8_t(buf, 61, fix_type); - _mav_put_uint8_t(buf, 62, satellites_visible); - _mav_put_uint16_t(buf, 63, yaw); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_INPUT, buf, MAVLINK_MSG_ID_GPS_INPUT_MIN_LEN, MAVLINK_MSG_ID_GPS_INPUT_LEN, MAVLINK_MSG_ID_GPS_INPUT_CRC); -#else - mavlink_gps_input_t *packet = (mavlink_gps_input_t *)msgbuf; - packet->time_usec = time_usec; - packet->time_week_ms = time_week_ms; - packet->lat = lat; - packet->lon = lon; - packet->alt = alt; - packet->hdop = hdop; - packet->vdop = vdop; - packet->vn = vn; - packet->ve = ve; - packet->vd = vd; - packet->speed_accuracy = speed_accuracy; - packet->horiz_accuracy = horiz_accuracy; - packet->vert_accuracy = vert_accuracy; - packet->ignore_flags = ignore_flags; - packet->time_week = time_week; - packet->gps_id = gps_id; - packet->fix_type = fix_type; - packet->satellites_visible = satellites_visible; - packet->yaw = yaw; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_INPUT, (const char *)packet, MAVLINK_MSG_ID_GPS_INPUT_MIN_LEN, MAVLINK_MSG_ID_GPS_INPUT_LEN, MAVLINK_MSG_ID_GPS_INPUT_CRC); -#endif -} -#endif - -#endif - -// MESSAGE GPS_INPUT UNPACKING - - -/** - * @brief Get field time_usec from gps_input message - * - * @return [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - */ -static inline uint64_t mavlink_msg_gps_input_get_time_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field gps_id from gps_input message - * - * @return ID of the GPS for multiple GPS inputs - */ -static inline uint8_t mavlink_msg_gps_input_get_gps_id(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 60); -} - -/** - * @brief Get field ignore_flags from gps_input message - * - * @return Bitmap indicating which GPS input flags fields to ignore. All other fields must be provided. - */ -static inline uint16_t mavlink_msg_gps_input_get_ignore_flags(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 56); -} - -/** - * @brief Get field time_week_ms from gps_input message - * - * @return [ms] GPS time (from start of GPS week) - */ -static inline uint32_t mavlink_msg_gps_input_get_time_week_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 8); -} - -/** - * @brief Get field time_week from gps_input message - * - * @return GPS week number - */ -static inline uint16_t mavlink_msg_gps_input_get_time_week(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 58); -} - -/** - * @brief Get field fix_type from gps_input message - * - * @return 0-1: no fix, 2: 2D fix, 3: 3D fix. 4: 3D with DGPS. 5: 3D with RTK - */ -static inline uint8_t mavlink_msg_gps_input_get_fix_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 61); -} - -/** - * @brief Get field lat from gps_input message - * - * @return [degE7] Latitude (WGS84) - */ -static inline int32_t mavlink_msg_gps_input_get_lat(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 12); -} - -/** - * @brief Get field lon from gps_input message - * - * @return [degE7] Longitude (WGS84) - */ -static inline int32_t mavlink_msg_gps_input_get_lon(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 16); -} - -/** - * @brief Get field alt from gps_input message - * - * @return [m] Altitude (MSL). Positive for up. - */ -static inline float mavlink_msg_gps_input_get_alt(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Get field hdop from gps_input message - * - * @return GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX - */ -static inline float mavlink_msg_gps_input_get_hdop(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Get field vdop from gps_input message - * - * @return GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX - */ -static inline float mavlink_msg_gps_input_get_vdop(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 28); -} - -/** - * @brief Get field vn from gps_input message - * - * @return [m/s] GPS velocity in north direction in earth-fixed NED frame - */ -static inline float mavlink_msg_gps_input_get_vn(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 32); -} - -/** - * @brief Get field ve from gps_input message - * - * @return [m/s] GPS velocity in east direction in earth-fixed NED frame - */ -static inline float mavlink_msg_gps_input_get_ve(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 36); -} - -/** - * @brief Get field vd from gps_input message - * - * @return [m/s] GPS velocity in down direction in earth-fixed NED frame - */ -static inline float mavlink_msg_gps_input_get_vd(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 40); -} - -/** - * @brief Get field speed_accuracy from gps_input message - * - * @return [m/s] GPS speed accuracy - */ -static inline float mavlink_msg_gps_input_get_speed_accuracy(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 44); -} - -/** - * @brief Get field horiz_accuracy from gps_input message - * - * @return [m] GPS horizontal accuracy - */ -static inline float mavlink_msg_gps_input_get_horiz_accuracy(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 48); -} - -/** - * @brief Get field vert_accuracy from gps_input message - * - * @return [m] GPS vertical accuracy - */ -static inline float mavlink_msg_gps_input_get_vert_accuracy(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 52); -} - -/** - * @brief Get field satellites_visible from gps_input message - * - * @return Number of satellites visible. - */ -static inline uint8_t mavlink_msg_gps_input_get_satellites_visible(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 62); -} - -/** - * @brief Get field yaw from gps_input message - * - * @return [cdeg] Yaw of vehicle relative to Earth's North, zero means not available, use 36000 for north - */ -static inline uint16_t mavlink_msg_gps_input_get_yaw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 63); -} - -/** - * @brief Decode a gps_input message into a struct - * - * @param msg The message to decode - * @param gps_input C-struct to decode the message contents into - */ -static inline void mavlink_msg_gps_input_decode(const mavlink_message_t* msg, mavlink_gps_input_t* gps_input) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - gps_input->time_usec = mavlink_msg_gps_input_get_time_usec(msg); - gps_input->time_week_ms = mavlink_msg_gps_input_get_time_week_ms(msg); - gps_input->lat = mavlink_msg_gps_input_get_lat(msg); - gps_input->lon = mavlink_msg_gps_input_get_lon(msg); - gps_input->alt = mavlink_msg_gps_input_get_alt(msg); - gps_input->hdop = mavlink_msg_gps_input_get_hdop(msg); - gps_input->vdop = mavlink_msg_gps_input_get_vdop(msg); - gps_input->vn = mavlink_msg_gps_input_get_vn(msg); - gps_input->ve = mavlink_msg_gps_input_get_ve(msg); - gps_input->vd = mavlink_msg_gps_input_get_vd(msg); - gps_input->speed_accuracy = mavlink_msg_gps_input_get_speed_accuracy(msg); - gps_input->horiz_accuracy = mavlink_msg_gps_input_get_horiz_accuracy(msg); - gps_input->vert_accuracy = mavlink_msg_gps_input_get_vert_accuracy(msg); - gps_input->ignore_flags = mavlink_msg_gps_input_get_ignore_flags(msg); - gps_input->time_week = mavlink_msg_gps_input_get_time_week(msg); - gps_input->gps_id = mavlink_msg_gps_input_get_gps_id(msg); - gps_input->fix_type = mavlink_msg_gps_input_get_fix_type(msg); - gps_input->satellites_visible = mavlink_msg_gps_input_get_satellites_visible(msg); - gps_input->yaw = mavlink_msg_gps_input_get_yaw(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_GPS_INPUT_LEN? msg->len : MAVLINK_MSG_ID_GPS_INPUT_LEN; - memset(gps_input, 0, MAVLINK_MSG_ID_GPS_INPUT_LEN); - memcpy(gps_input, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_gps_raw_int.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_gps_raw_int.h deleted file mode 100644 index 5fdbef07..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_gps_raw_int.h +++ /dev/null @@ -1,588 +0,0 @@ -#pragma once -// MESSAGE GPS_RAW_INT PACKING - -#define MAVLINK_MSG_ID_GPS_RAW_INT 24 - -MAVPACKED( -typedef struct __mavlink_gps_raw_int_t { - uint64_t time_usec; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/ - int32_t lat; /*< [degE7] Latitude (WGS84, EGM96 ellipsoid)*/ - int32_t lon; /*< [degE7] Longitude (WGS84, EGM96 ellipsoid)*/ - int32_t alt; /*< [mm] Altitude (MSL). Positive for up. Note that virtually all GPS modules provide the MSL altitude in addition to the WGS84 altitude.*/ - uint16_t eph; /*< GPS HDOP horizontal dilution of position (unitless * 100). If unknown, set to: UINT16_MAX*/ - uint16_t epv; /*< GPS VDOP vertical dilution of position (unitless * 100). If unknown, set to: UINT16_MAX*/ - uint16_t vel; /*< [cm/s] GPS ground speed. If unknown, set to: UINT16_MAX*/ - uint16_t cog; /*< [cdeg] Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX*/ - uint8_t fix_type; /*< GPS fix type.*/ - uint8_t satellites_visible; /*< Number of satellites visible. If unknown, set to UINT8_MAX*/ - int32_t alt_ellipsoid; /*< [mm] Altitude (above WGS84, EGM96 ellipsoid). Positive for up.*/ - uint32_t h_acc; /*< [mm] Position uncertainty.*/ - uint32_t v_acc; /*< [mm] Altitude uncertainty.*/ - uint32_t vel_acc; /*< [mm] Speed uncertainty.*/ - uint32_t hdg_acc; /*< [degE5] Heading / track uncertainty*/ - uint16_t yaw; /*< [cdeg] Yaw in earth frame from north. Use 0 if this GPS does not provide yaw. Use UINT16_MAX if this GPS is configured to provide yaw and is currently unable to provide it. Use 36000 for north.*/ -}) mavlink_gps_raw_int_t; - -#define MAVLINK_MSG_ID_GPS_RAW_INT_LEN 52 -#define MAVLINK_MSG_ID_GPS_RAW_INT_MIN_LEN 30 -#define MAVLINK_MSG_ID_24_LEN 52 -#define MAVLINK_MSG_ID_24_MIN_LEN 30 - -#define MAVLINK_MSG_ID_GPS_RAW_INT_CRC 24 -#define MAVLINK_MSG_ID_24_CRC 24 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_GPS_RAW_INT { \ - 24, \ - "GPS_RAW_INT", \ - 16, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_gps_raw_int_t, time_usec) }, \ - { "fix_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 28, offsetof(mavlink_gps_raw_int_t, fix_type) }, \ - { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_gps_raw_int_t, lat) }, \ - { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_gps_raw_int_t, lon) }, \ - { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_gps_raw_int_t, alt) }, \ - { "eph", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_gps_raw_int_t, eph) }, \ - { "epv", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_gps_raw_int_t, epv) }, \ - { "vel", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_gps_raw_int_t, vel) }, \ - { "cog", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_gps_raw_int_t, cog) }, \ - { "satellites_visible", NULL, MAVLINK_TYPE_UINT8_T, 0, 29, offsetof(mavlink_gps_raw_int_t, satellites_visible) }, \ - { "alt_ellipsoid", NULL, MAVLINK_TYPE_INT32_T, 0, 30, offsetof(mavlink_gps_raw_int_t, alt_ellipsoid) }, \ - { "h_acc", NULL, MAVLINK_TYPE_UINT32_T, 0, 34, offsetof(mavlink_gps_raw_int_t, h_acc) }, \ - { "v_acc", NULL, MAVLINK_TYPE_UINT32_T, 0, 38, offsetof(mavlink_gps_raw_int_t, v_acc) }, \ - { "vel_acc", NULL, MAVLINK_TYPE_UINT32_T, 0, 42, offsetof(mavlink_gps_raw_int_t, vel_acc) }, \ - { "hdg_acc", NULL, MAVLINK_TYPE_UINT32_T, 0, 46, offsetof(mavlink_gps_raw_int_t, hdg_acc) }, \ - { "yaw", NULL, MAVLINK_TYPE_UINT16_T, 0, 50, offsetof(mavlink_gps_raw_int_t, yaw) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_GPS_RAW_INT { \ - "GPS_RAW_INT", \ - 16, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_gps_raw_int_t, time_usec) }, \ - { "fix_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 28, offsetof(mavlink_gps_raw_int_t, fix_type) }, \ - { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_gps_raw_int_t, lat) }, \ - { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_gps_raw_int_t, lon) }, \ - { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_gps_raw_int_t, alt) }, \ - { "eph", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_gps_raw_int_t, eph) }, \ - { "epv", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_gps_raw_int_t, epv) }, \ - { "vel", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_gps_raw_int_t, vel) }, \ - { "cog", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_gps_raw_int_t, cog) }, \ - { "satellites_visible", NULL, MAVLINK_TYPE_UINT8_T, 0, 29, offsetof(mavlink_gps_raw_int_t, satellites_visible) }, \ - { "alt_ellipsoid", NULL, MAVLINK_TYPE_INT32_T, 0, 30, offsetof(mavlink_gps_raw_int_t, alt_ellipsoid) }, \ - { "h_acc", NULL, MAVLINK_TYPE_UINT32_T, 0, 34, offsetof(mavlink_gps_raw_int_t, h_acc) }, \ - { "v_acc", NULL, MAVLINK_TYPE_UINT32_T, 0, 38, offsetof(mavlink_gps_raw_int_t, v_acc) }, \ - { "vel_acc", NULL, MAVLINK_TYPE_UINT32_T, 0, 42, offsetof(mavlink_gps_raw_int_t, vel_acc) }, \ - { "hdg_acc", NULL, MAVLINK_TYPE_UINT32_T, 0, 46, offsetof(mavlink_gps_raw_int_t, hdg_acc) }, \ - { "yaw", NULL, MAVLINK_TYPE_UINT16_T, 0, 50, offsetof(mavlink_gps_raw_int_t, yaw) }, \ - } \ -} -#endif - -/** - * @brief Pack a gps_raw_int message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @param fix_type GPS fix type. - * @param lat [degE7] Latitude (WGS84, EGM96 ellipsoid) - * @param lon [degE7] Longitude (WGS84, EGM96 ellipsoid) - * @param alt [mm] Altitude (MSL). Positive for up. Note that virtually all GPS modules provide the MSL altitude in addition to the WGS84 altitude. - * @param eph GPS HDOP horizontal dilution of position (unitless * 100). If unknown, set to: UINT16_MAX - * @param epv GPS VDOP vertical dilution of position (unitless * 100). If unknown, set to: UINT16_MAX - * @param vel [cm/s] GPS ground speed. If unknown, set to: UINT16_MAX - * @param cog [cdeg] Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX - * @param satellites_visible Number of satellites visible. If unknown, set to UINT8_MAX - * @param alt_ellipsoid [mm] Altitude (above WGS84, EGM96 ellipsoid). Positive for up. - * @param h_acc [mm] Position uncertainty. - * @param v_acc [mm] Altitude uncertainty. - * @param vel_acc [mm] Speed uncertainty. - * @param hdg_acc [degE5] Heading / track uncertainty - * @param yaw [cdeg] Yaw in earth frame from north. Use 0 if this GPS does not provide yaw. Use UINT16_MAX if this GPS is configured to provide yaw and is currently unable to provide it. Use 36000 for north. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_gps_raw_int_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint64_t time_usec, uint8_t fix_type, int32_t lat, int32_t lon, int32_t alt, uint16_t eph, uint16_t epv, uint16_t vel, uint16_t cog, uint8_t satellites_visible, int32_t alt_ellipsoid, uint32_t h_acc, uint32_t v_acc, uint32_t vel_acc, uint32_t hdg_acc, uint16_t yaw) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_GPS_RAW_INT_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_int32_t(buf, 8, lat); - _mav_put_int32_t(buf, 12, lon); - _mav_put_int32_t(buf, 16, alt); - _mav_put_uint16_t(buf, 20, eph); - _mav_put_uint16_t(buf, 22, epv); - _mav_put_uint16_t(buf, 24, vel); - _mav_put_uint16_t(buf, 26, cog); - _mav_put_uint8_t(buf, 28, fix_type); - _mav_put_uint8_t(buf, 29, satellites_visible); - _mav_put_int32_t(buf, 30, alt_ellipsoid); - _mav_put_uint32_t(buf, 34, h_acc); - _mav_put_uint32_t(buf, 38, v_acc); - _mav_put_uint32_t(buf, 42, vel_acc); - _mav_put_uint32_t(buf, 46, hdg_acc); - _mav_put_uint16_t(buf, 50, yaw); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS_RAW_INT_LEN); -#else - mavlink_gps_raw_int_t packet; - packet.time_usec = time_usec; - packet.lat = lat; - packet.lon = lon; - packet.alt = alt; - packet.eph = eph; - packet.epv = epv; - packet.vel = vel; - packet.cog = cog; - packet.fix_type = fix_type; - packet.satellites_visible = satellites_visible; - packet.alt_ellipsoid = alt_ellipsoid; - packet.h_acc = h_acc; - packet.v_acc = v_acc; - packet.vel_acc = vel_acc; - packet.hdg_acc = hdg_acc; - packet.yaw = yaw; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS_RAW_INT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_GPS_RAW_INT; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS_RAW_INT_MIN_LEN, MAVLINK_MSG_ID_GPS_RAW_INT_LEN, MAVLINK_MSG_ID_GPS_RAW_INT_CRC); -} - -/** - * @brief Pack a gps_raw_int message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @param fix_type GPS fix type. - * @param lat [degE7] Latitude (WGS84, EGM96 ellipsoid) - * @param lon [degE7] Longitude (WGS84, EGM96 ellipsoid) - * @param alt [mm] Altitude (MSL). Positive for up. Note that virtually all GPS modules provide the MSL altitude in addition to the WGS84 altitude. - * @param eph GPS HDOP horizontal dilution of position (unitless * 100). If unknown, set to: UINT16_MAX - * @param epv GPS VDOP vertical dilution of position (unitless * 100). If unknown, set to: UINT16_MAX - * @param vel [cm/s] GPS ground speed. If unknown, set to: UINT16_MAX - * @param cog [cdeg] Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX - * @param satellites_visible Number of satellites visible. If unknown, set to UINT8_MAX - * @param alt_ellipsoid [mm] Altitude (above WGS84, EGM96 ellipsoid). Positive for up. - * @param h_acc [mm] Position uncertainty. - * @param v_acc [mm] Altitude uncertainty. - * @param vel_acc [mm] Speed uncertainty. - * @param hdg_acc [degE5] Heading / track uncertainty - * @param yaw [cdeg] Yaw in earth frame from north. Use 0 if this GPS does not provide yaw. Use UINT16_MAX if this GPS is configured to provide yaw and is currently unable to provide it. Use 36000 for north. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_gps_raw_int_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint64_t time_usec,uint8_t fix_type,int32_t lat,int32_t lon,int32_t alt,uint16_t eph,uint16_t epv,uint16_t vel,uint16_t cog,uint8_t satellites_visible,int32_t alt_ellipsoid,uint32_t h_acc,uint32_t v_acc,uint32_t vel_acc,uint32_t hdg_acc,uint16_t yaw) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_GPS_RAW_INT_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_int32_t(buf, 8, lat); - _mav_put_int32_t(buf, 12, lon); - _mav_put_int32_t(buf, 16, alt); - _mav_put_uint16_t(buf, 20, eph); - _mav_put_uint16_t(buf, 22, epv); - _mav_put_uint16_t(buf, 24, vel); - _mav_put_uint16_t(buf, 26, cog); - _mav_put_uint8_t(buf, 28, fix_type); - _mav_put_uint8_t(buf, 29, satellites_visible); - _mav_put_int32_t(buf, 30, alt_ellipsoid); - _mav_put_uint32_t(buf, 34, h_acc); - _mav_put_uint32_t(buf, 38, v_acc); - _mav_put_uint32_t(buf, 42, vel_acc); - _mav_put_uint32_t(buf, 46, hdg_acc); - _mav_put_uint16_t(buf, 50, yaw); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS_RAW_INT_LEN); -#else - mavlink_gps_raw_int_t packet; - packet.time_usec = time_usec; - packet.lat = lat; - packet.lon = lon; - packet.alt = alt; - packet.eph = eph; - packet.epv = epv; - packet.vel = vel; - packet.cog = cog; - packet.fix_type = fix_type; - packet.satellites_visible = satellites_visible; - packet.alt_ellipsoid = alt_ellipsoid; - packet.h_acc = h_acc; - packet.v_acc = v_acc; - packet.vel_acc = vel_acc; - packet.hdg_acc = hdg_acc; - packet.yaw = yaw; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS_RAW_INT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_GPS_RAW_INT; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GPS_RAW_INT_MIN_LEN, MAVLINK_MSG_ID_GPS_RAW_INT_LEN, MAVLINK_MSG_ID_GPS_RAW_INT_CRC); -} - -/** - * @brief Encode a gps_raw_int struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param gps_raw_int C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_gps_raw_int_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gps_raw_int_t* gps_raw_int) -{ - return mavlink_msg_gps_raw_int_pack(system_id, component_id, msg, gps_raw_int->time_usec, gps_raw_int->fix_type, gps_raw_int->lat, gps_raw_int->lon, gps_raw_int->alt, gps_raw_int->eph, gps_raw_int->epv, gps_raw_int->vel, gps_raw_int->cog, gps_raw_int->satellites_visible, gps_raw_int->alt_ellipsoid, gps_raw_int->h_acc, gps_raw_int->v_acc, gps_raw_int->vel_acc, gps_raw_int->hdg_acc, gps_raw_int->yaw); -} - -/** - * @brief Encode a gps_raw_int struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param gps_raw_int C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_gps_raw_int_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_gps_raw_int_t* gps_raw_int) -{ - return mavlink_msg_gps_raw_int_pack_chan(system_id, component_id, chan, msg, gps_raw_int->time_usec, gps_raw_int->fix_type, gps_raw_int->lat, gps_raw_int->lon, gps_raw_int->alt, gps_raw_int->eph, gps_raw_int->epv, gps_raw_int->vel, gps_raw_int->cog, gps_raw_int->satellites_visible, gps_raw_int->alt_ellipsoid, gps_raw_int->h_acc, gps_raw_int->v_acc, gps_raw_int->vel_acc, gps_raw_int->hdg_acc, gps_raw_int->yaw); -} - -/** - * @brief Send a gps_raw_int message - * @param chan MAVLink channel to send the message - * - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @param fix_type GPS fix type. - * @param lat [degE7] Latitude (WGS84, EGM96 ellipsoid) - * @param lon [degE7] Longitude (WGS84, EGM96 ellipsoid) - * @param alt [mm] Altitude (MSL). Positive for up. Note that virtually all GPS modules provide the MSL altitude in addition to the WGS84 altitude. - * @param eph GPS HDOP horizontal dilution of position (unitless * 100). If unknown, set to: UINT16_MAX - * @param epv GPS VDOP vertical dilution of position (unitless * 100). If unknown, set to: UINT16_MAX - * @param vel [cm/s] GPS ground speed. If unknown, set to: UINT16_MAX - * @param cog [cdeg] Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX - * @param satellites_visible Number of satellites visible. If unknown, set to UINT8_MAX - * @param alt_ellipsoid [mm] Altitude (above WGS84, EGM96 ellipsoid). Positive for up. - * @param h_acc [mm] Position uncertainty. - * @param v_acc [mm] Altitude uncertainty. - * @param vel_acc [mm] Speed uncertainty. - * @param hdg_acc [degE5] Heading / track uncertainty - * @param yaw [cdeg] Yaw in earth frame from north. Use 0 if this GPS does not provide yaw. Use UINT16_MAX if this GPS is configured to provide yaw and is currently unable to provide it. Use 36000 for north. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_gps_raw_int_send(mavlink_channel_t chan, uint64_t time_usec, uint8_t fix_type, int32_t lat, int32_t lon, int32_t alt, uint16_t eph, uint16_t epv, uint16_t vel, uint16_t cog, uint8_t satellites_visible, int32_t alt_ellipsoid, uint32_t h_acc, uint32_t v_acc, uint32_t vel_acc, uint32_t hdg_acc, uint16_t yaw) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_GPS_RAW_INT_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_int32_t(buf, 8, lat); - _mav_put_int32_t(buf, 12, lon); - _mav_put_int32_t(buf, 16, alt); - _mav_put_uint16_t(buf, 20, eph); - _mav_put_uint16_t(buf, 22, epv); - _mav_put_uint16_t(buf, 24, vel); - _mav_put_uint16_t(buf, 26, cog); - _mav_put_uint8_t(buf, 28, fix_type); - _mav_put_uint8_t(buf, 29, satellites_visible); - _mav_put_int32_t(buf, 30, alt_ellipsoid); - _mav_put_uint32_t(buf, 34, h_acc); - _mav_put_uint32_t(buf, 38, v_acc); - _mav_put_uint32_t(buf, 42, vel_acc); - _mav_put_uint32_t(buf, 46, hdg_acc); - _mav_put_uint16_t(buf, 50, yaw); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RAW_INT, buf, MAVLINK_MSG_ID_GPS_RAW_INT_MIN_LEN, MAVLINK_MSG_ID_GPS_RAW_INT_LEN, MAVLINK_MSG_ID_GPS_RAW_INT_CRC); -#else - mavlink_gps_raw_int_t packet; - packet.time_usec = time_usec; - packet.lat = lat; - packet.lon = lon; - packet.alt = alt; - packet.eph = eph; - packet.epv = epv; - packet.vel = vel; - packet.cog = cog; - packet.fix_type = fix_type; - packet.satellites_visible = satellites_visible; - packet.alt_ellipsoid = alt_ellipsoid; - packet.h_acc = h_acc; - packet.v_acc = v_acc; - packet.vel_acc = vel_acc; - packet.hdg_acc = hdg_acc; - packet.yaw = yaw; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RAW_INT, (const char *)&packet, MAVLINK_MSG_ID_GPS_RAW_INT_MIN_LEN, MAVLINK_MSG_ID_GPS_RAW_INT_LEN, MAVLINK_MSG_ID_GPS_RAW_INT_CRC); -#endif -} - -/** - * @brief Send a gps_raw_int message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_gps_raw_int_send_struct(mavlink_channel_t chan, const mavlink_gps_raw_int_t* gps_raw_int) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_gps_raw_int_send(chan, gps_raw_int->time_usec, gps_raw_int->fix_type, gps_raw_int->lat, gps_raw_int->lon, gps_raw_int->alt, gps_raw_int->eph, gps_raw_int->epv, gps_raw_int->vel, gps_raw_int->cog, gps_raw_int->satellites_visible, gps_raw_int->alt_ellipsoid, gps_raw_int->h_acc, gps_raw_int->v_acc, gps_raw_int->vel_acc, gps_raw_int->hdg_acc, gps_raw_int->yaw); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RAW_INT, (const char *)gps_raw_int, MAVLINK_MSG_ID_GPS_RAW_INT_MIN_LEN, MAVLINK_MSG_ID_GPS_RAW_INT_LEN, MAVLINK_MSG_ID_GPS_RAW_INT_CRC); -#endif -} - -#if MAVLINK_MSG_ID_GPS_RAW_INT_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_gps_raw_int_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, uint8_t fix_type, int32_t lat, int32_t lon, int32_t alt, uint16_t eph, uint16_t epv, uint16_t vel, uint16_t cog, uint8_t satellites_visible, int32_t alt_ellipsoid, uint32_t h_acc, uint32_t v_acc, uint32_t vel_acc, uint32_t hdg_acc, uint16_t yaw) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_int32_t(buf, 8, lat); - _mav_put_int32_t(buf, 12, lon); - _mav_put_int32_t(buf, 16, alt); - _mav_put_uint16_t(buf, 20, eph); - _mav_put_uint16_t(buf, 22, epv); - _mav_put_uint16_t(buf, 24, vel); - _mav_put_uint16_t(buf, 26, cog); - _mav_put_uint8_t(buf, 28, fix_type); - _mav_put_uint8_t(buf, 29, satellites_visible); - _mav_put_int32_t(buf, 30, alt_ellipsoid); - _mav_put_uint32_t(buf, 34, h_acc); - _mav_put_uint32_t(buf, 38, v_acc); - _mav_put_uint32_t(buf, 42, vel_acc); - _mav_put_uint32_t(buf, 46, hdg_acc); - _mav_put_uint16_t(buf, 50, yaw); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RAW_INT, buf, MAVLINK_MSG_ID_GPS_RAW_INT_MIN_LEN, MAVLINK_MSG_ID_GPS_RAW_INT_LEN, MAVLINK_MSG_ID_GPS_RAW_INT_CRC); -#else - mavlink_gps_raw_int_t *packet = (mavlink_gps_raw_int_t *)msgbuf; - packet->time_usec = time_usec; - packet->lat = lat; - packet->lon = lon; - packet->alt = alt; - packet->eph = eph; - packet->epv = epv; - packet->vel = vel; - packet->cog = cog; - packet->fix_type = fix_type; - packet->satellites_visible = satellites_visible; - packet->alt_ellipsoid = alt_ellipsoid; - packet->h_acc = h_acc; - packet->v_acc = v_acc; - packet->vel_acc = vel_acc; - packet->hdg_acc = hdg_acc; - packet->yaw = yaw; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RAW_INT, (const char *)packet, MAVLINK_MSG_ID_GPS_RAW_INT_MIN_LEN, MAVLINK_MSG_ID_GPS_RAW_INT_LEN, MAVLINK_MSG_ID_GPS_RAW_INT_CRC); -#endif -} -#endif - -#endif - -// MESSAGE GPS_RAW_INT UNPACKING - - -/** - * @brief Get field time_usec from gps_raw_int message - * - * @return [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - */ -static inline uint64_t mavlink_msg_gps_raw_int_get_time_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field fix_type from gps_raw_int message - * - * @return GPS fix type. - */ -static inline uint8_t mavlink_msg_gps_raw_int_get_fix_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 28); -} - -/** - * @brief Get field lat from gps_raw_int message - * - * @return [degE7] Latitude (WGS84, EGM96 ellipsoid) - */ -static inline int32_t mavlink_msg_gps_raw_int_get_lat(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 8); -} - -/** - * @brief Get field lon from gps_raw_int message - * - * @return [degE7] Longitude (WGS84, EGM96 ellipsoid) - */ -static inline int32_t mavlink_msg_gps_raw_int_get_lon(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 12); -} - -/** - * @brief Get field alt from gps_raw_int message - * - * @return [mm] Altitude (MSL). Positive for up. Note that virtually all GPS modules provide the MSL altitude in addition to the WGS84 altitude. - */ -static inline int32_t mavlink_msg_gps_raw_int_get_alt(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 16); -} - -/** - * @brief Get field eph from gps_raw_int message - * - * @return GPS HDOP horizontal dilution of position (unitless * 100). If unknown, set to: UINT16_MAX - */ -static inline uint16_t mavlink_msg_gps_raw_int_get_eph(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 20); -} - -/** - * @brief Get field epv from gps_raw_int message - * - * @return GPS VDOP vertical dilution of position (unitless * 100). If unknown, set to: UINT16_MAX - */ -static inline uint16_t mavlink_msg_gps_raw_int_get_epv(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 22); -} - -/** - * @brief Get field vel from gps_raw_int message - * - * @return [cm/s] GPS ground speed. If unknown, set to: UINT16_MAX - */ -static inline uint16_t mavlink_msg_gps_raw_int_get_vel(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 24); -} - -/** - * @brief Get field cog from gps_raw_int message - * - * @return [cdeg] Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX - */ -static inline uint16_t mavlink_msg_gps_raw_int_get_cog(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 26); -} - -/** - * @brief Get field satellites_visible from gps_raw_int message - * - * @return Number of satellites visible. If unknown, set to UINT8_MAX - */ -static inline uint8_t mavlink_msg_gps_raw_int_get_satellites_visible(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 29); -} - -/** - * @brief Get field alt_ellipsoid from gps_raw_int message - * - * @return [mm] Altitude (above WGS84, EGM96 ellipsoid). Positive for up. - */ -static inline int32_t mavlink_msg_gps_raw_int_get_alt_ellipsoid(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 30); -} - -/** - * @brief Get field h_acc from gps_raw_int message - * - * @return [mm] Position uncertainty. - */ -static inline uint32_t mavlink_msg_gps_raw_int_get_h_acc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 34); -} - -/** - * @brief Get field v_acc from gps_raw_int message - * - * @return [mm] Altitude uncertainty. - */ -static inline uint32_t mavlink_msg_gps_raw_int_get_v_acc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 38); -} - -/** - * @brief Get field vel_acc from gps_raw_int message - * - * @return [mm] Speed uncertainty. - */ -static inline uint32_t mavlink_msg_gps_raw_int_get_vel_acc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 42); -} - -/** - * @brief Get field hdg_acc from gps_raw_int message - * - * @return [degE5] Heading / track uncertainty - */ -static inline uint32_t mavlink_msg_gps_raw_int_get_hdg_acc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 46); -} - -/** - * @brief Get field yaw from gps_raw_int message - * - * @return [cdeg] Yaw in earth frame from north. Use 0 if this GPS does not provide yaw. Use UINT16_MAX if this GPS is configured to provide yaw and is currently unable to provide it. Use 36000 for north. - */ -static inline uint16_t mavlink_msg_gps_raw_int_get_yaw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 50); -} - -/** - * @brief Decode a gps_raw_int message into a struct - * - * @param msg The message to decode - * @param gps_raw_int C-struct to decode the message contents into - */ -static inline void mavlink_msg_gps_raw_int_decode(const mavlink_message_t* msg, mavlink_gps_raw_int_t* gps_raw_int) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - gps_raw_int->time_usec = mavlink_msg_gps_raw_int_get_time_usec(msg); - gps_raw_int->lat = mavlink_msg_gps_raw_int_get_lat(msg); - gps_raw_int->lon = mavlink_msg_gps_raw_int_get_lon(msg); - gps_raw_int->alt = mavlink_msg_gps_raw_int_get_alt(msg); - gps_raw_int->eph = mavlink_msg_gps_raw_int_get_eph(msg); - gps_raw_int->epv = mavlink_msg_gps_raw_int_get_epv(msg); - gps_raw_int->vel = mavlink_msg_gps_raw_int_get_vel(msg); - gps_raw_int->cog = mavlink_msg_gps_raw_int_get_cog(msg); - gps_raw_int->fix_type = mavlink_msg_gps_raw_int_get_fix_type(msg); - gps_raw_int->satellites_visible = mavlink_msg_gps_raw_int_get_satellites_visible(msg); - gps_raw_int->alt_ellipsoid = mavlink_msg_gps_raw_int_get_alt_ellipsoid(msg); - gps_raw_int->h_acc = mavlink_msg_gps_raw_int_get_h_acc(msg); - gps_raw_int->v_acc = mavlink_msg_gps_raw_int_get_v_acc(msg); - gps_raw_int->vel_acc = mavlink_msg_gps_raw_int_get_vel_acc(msg); - gps_raw_int->hdg_acc = mavlink_msg_gps_raw_int_get_hdg_acc(msg); - gps_raw_int->yaw = mavlink_msg_gps_raw_int_get_yaw(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_GPS_RAW_INT_LEN? msg->len : MAVLINK_MSG_ID_GPS_RAW_INT_LEN; - memset(gps_raw_int, 0, MAVLINK_MSG_ID_GPS_RAW_INT_LEN); - memcpy(gps_raw_int, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_gps_rtcm_data.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_gps_rtcm_data.h deleted file mode 100644 index a6f861ee..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_gps_rtcm_data.h +++ /dev/null @@ -1,255 +0,0 @@ -#pragma once -// MESSAGE GPS_RTCM_DATA PACKING - -#define MAVLINK_MSG_ID_GPS_RTCM_DATA 233 - - -typedef struct __mavlink_gps_rtcm_data_t { - uint8_t flags; /*< LSB: 1 means message is fragmented, next 2 bits are the fragment ID, the remaining 5 bits are used for the sequence ID. Messages are only to be flushed to the GPS when the entire message has been reconstructed on the autopilot. The fragment ID specifies which order the fragments should be assembled into a buffer, while the sequence ID is used to detect a mismatch between different buffers. The buffer is considered fully reconstructed when either all 4 fragments are present, or all the fragments before the first fragment with a non full payload is received. This management is used to ensure that normal GPS operation doesn't corrupt RTCM data, and to recover from a unreliable transport delivery order.*/ - uint8_t len; /*< [bytes] data length*/ - uint8_t data[180]; /*< RTCM message (may be fragmented)*/ -} mavlink_gps_rtcm_data_t; - -#define MAVLINK_MSG_ID_GPS_RTCM_DATA_LEN 182 -#define MAVLINK_MSG_ID_GPS_RTCM_DATA_MIN_LEN 182 -#define MAVLINK_MSG_ID_233_LEN 182 -#define MAVLINK_MSG_ID_233_MIN_LEN 182 - -#define MAVLINK_MSG_ID_GPS_RTCM_DATA_CRC 35 -#define MAVLINK_MSG_ID_233_CRC 35 - -#define MAVLINK_MSG_GPS_RTCM_DATA_FIELD_DATA_LEN 180 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_GPS_RTCM_DATA { \ - 233, \ - "GPS_RTCM_DATA", \ - 3, \ - { { "flags", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_gps_rtcm_data_t, flags) }, \ - { "len", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_gps_rtcm_data_t, len) }, \ - { "data", NULL, MAVLINK_TYPE_UINT8_T, 180, 2, offsetof(mavlink_gps_rtcm_data_t, data) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_GPS_RTCM_DATA { \ - "GPS_RTCM_DATA", \ - 3, \ - { { "flags", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_gps_rtcm_data_t, flags) }, \ - { "len", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_gps_rtcm_data_t, len) }, \ - { "data", NULL, MAVLINK_TYPE_UINT8_T, 180, 2, offsetof(mavlink_gps_rtcm_data_t, data) }, \ - } \ -} -#endif - -/** - * @brief Pack a gps_rtcm_data message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param flags LSB: 1 means message is fragmented, next 2 bits are the fragment ID, the remaining 5 bits are used for the sequence ID. Messages are only to be flushed to the GPS when the entire message has been reconstructed on the autopilot. The fragment ID specifies which order the fragments should be assembled into a buffer, while the sequence ID is used to detect a mismatch between different buffers. The buffer is considered fully reconstructed when either all 4 fragments are present, or all the fragments before the first fragment with a non full payload is received. This management is used to ensure that normal GPS operation doesn't corrupt RTCM data, and to recover from a unreliable transport delivery order. - * @param len [bytes] data length - * @param data RTCM message (may be fragmented) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_gps_rtcm_data_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t flags, uint8_t len, const uint8_t *data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_GPS_RTCM_DATA_LEN]; - _mav_put_uint8_t(buf, 0, flags); - _mav_put_uint8_t(buf, 1, len); - _mav_put_uint8_t_array(buf, 2, data, 180); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS_RTCM_DATA_LEN); -#else - mavlink_gps_rtcm_data_t packet; - packet.flags = flags; - packet.len = len; - mav_array_memcpy(packet.data, data, sizeof(uint8_t)*180); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS_RTCM_DATA_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_GPS_RTCM_DATA; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS_RTCM_DATA_MIN_LEN, MAVLINK_MSG_ID_GPS_RTCM_DATA_LEN, MAVLINK_MSG_ID_GPS_RTCM_DATA_CRC); -} - -/** - * @brief Pack a gps_rtcm_data message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param flags LSB: 1 means message is fragmented, next 2 bits are the fragment ID, the remaining 5 bits are used for the sequence ID. Messages are only to be flushed to the GPS when the entire message has been reconstructed on the autopilot. The fragment ID specifies which order the fragments should be assembled into a buffer, while the sequence ID is used to detect a mismatch between different buffers. The buffer is considered fully reconstructed when either all 4 fragments are present, or all the fragments before the first fragment with a non full payload is received. This management is used to ensure that normal GPS operation doesn't corrupt RTCM data, and to recover from a unreliable transport delivery order. - * @param len [bytes] data length - * @param data RTCM message (may be fragmented) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_gps_rtcm_data_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t flags,uint8_t len,const uint8_t *data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_GPS_RTCM_DATA_LEN]; - _mav_put_uint8_t(buf, 0, flags); - _mav_put_uint8_t(buf, 1, len); - _mav_put_uint8_t_array(buf, 2, data, 180); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS_RTCM_DATA_LEN); -#else - mavlink_gps_rtcm_data_t packet; - packet.flags = flags; - packet.len = len; - mav_array_memcpy(packet.data, data, sizeof(uint8_t)*180); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS_RTCM_DATA_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_GPS_RTCM_DATA; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GPS_RTCM_DATA_MIN_LEN, MAVLINK_MSG_ID_GPS_RTCM_DATA_LEN, MAVLINK_MSG_ID_GPS_RTCM_DATA_CRC); -} - -/** - * @brief Encode a gps_rtcm_data struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param gps_rtcm_data C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_gps_rtcm_data_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gps_rtcm_data_t* gps_rtcm_data) -{ - return mavlink_msg_gps_rtcm_data_pack(system_id, component_id, msg, gps_rtcm_data->flags, gps_rtcm_data->len, gps_rtcm_data->data); -} - -/** - * @brief Encode a gps_rtcm_data struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param gps_rtcm_data C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_gps_rtcm_data_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_gps_rtcm_data_t* gps_rtcm_data) -{ - return mavlink_msg_gps_rtcm_data_pack_chan(system_id, component_id, chan, msg, gps_rtcm_data->flags, gps_rtcm_data->len, gps_rtcm_data->data); -} - -/** - * @brief Send a gps_rtcm_data message - * @param chan MAVLink channel to send the message - * - * @param flags LSB: 1 means message is fragmented, next 2 bits are the fragment ID, the remaining 5 bits are used for the sequence ID. Messages are only to be flushed to the GPS when the entire message has been reconstructed on the autopilot. The fragment ID specifies which order the fragments should be assembled into a buffer, while the sequence ID is used to detect a mismatch between different buffers. The buffer is considered fully reconstructed when either all 4 fragments are present, or all the fragments before the first fragment with a non full payload is received. This management is used to ensure that normal GPS operation doesn't corrupt RTCM data, and to recover from a unreliable transport delivery order. - * @param len [bytes] data length - * @param data RTCM message (may be fragmented) - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_gps_rtcm_data_send(mavlink_channel_t chan, uint8_t flags, uint8_t len, const uint8_t *data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_GPS_RTCM_DATA_LEN]; - _mav_put_uint8_t(buf, 0, flags); - _mav_put_uint8_t(buf, 1, len); - _mav_put_uint8_t_array(buf, 2, data, 180); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RTCM_DATA, buf, MAVLINK_MSG_ID_GPS_RTCM_DATA_MIN_LEN, MAVLINK_MSG_ID_GPS_RTCM_DATA_LEN, MAVLINK_MSG_ID_GPS_RTCM_DATA_CRC); -#else - mavlink_gps_rtcm_data_t packet; - packet.flags = flags; - packet.len = len; - mav_array_memcpy(packet.data, data, sizeof(uint8_t)*180); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RTCM_DATA, (const char *)&packet, MAVLINK_MSG_ID_GPS_RTCM_DATA_MIN_LEN, MAVLINK_MSG_ID_GPS_RTCM_DATA_LEN, MAVLINK_MSG_ID_GPS_RTCM_DATA_CRC); -#endif -} - -/** - * @brief Send a gps_rtcm_data message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_gps_rtcm_data_send_struct(mavlink_channel_t chan, const mavlink_gps_rtcm_data_t* gps_rtcm_data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_gps_rtcm_data_send(chan, gps_rtcm_data->flags, gps_rtcm_data->len, gps_rtcm_data->data); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RTCM_DATA, (const char *)gps_rtcm_data, MAVLINK_MSG_ID_GPS_RTCM_DATA_MIN_LEN, MAVLINK_MSG_ID_GPS_RTCM_DATA_LEN, MAVLINK_MSG_ID_GPS_RTCM_DATA_CRC); -#endif -} - -#if MAVLINK_MSG_ID_GPS_RTCM_DATA_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_gps_rtcm_data_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t flags, uint8_t len, const uint8_t *data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint8_t(buf, 0, flags); - _mav_put_uint8_t(buf, 1, len); - _mav_put_uint8_t_array(buf, 2, data, 180); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RTCM_DATA, buf, MAVLINK_MSG_ID_GPS_RTCM_DATA_MIN_LEN, MAVLINK_MSG_ID_GPS_RTCM_DATA_LEN, MAVLINK_MSG_ID_GPS_RTCM_DATA_CRC); -#else - mavlink_gps_rtcm_data_t *packet = (mavlink_gps_rtcm_data_t *)msgbuf; - packet->flags = flags; - packet->len = len; - mav_array_memcpy(packet->data, data, sizeof(uint8_t)*180); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RTCM_DATA, (const char *)packet, MAVLINK_MSG_ID_GPS_RTCM_DATA_MIN_LEN, MAVLINK_MSG_ID_GPS_RTCM_DATA_LEN, MAVLINK_MSG_ID_GPS_RTCM_DATA_CRC); -#endif -} -#endif - -#endif - -// MESSAGE GPS_RTCM_DATA UNPACKING - - -/** - * @brief Get field flags from gps_rtcm_data message - * - * @return LSB: 1 means message is fragmented, next 2 bits are the fragment ID, the remaining 5 bits are used for the sequence ID. Messages are only to be flushed to the GPS when the entire message has been reconstructed on the autopilot. The fragment ID specifies which order the fragments should be assembled into a buffer, while the sequence ID is used to detect a mismatch between different buffers. The buffer is considered fully reconstructed when either all 4 fragments are present, or all the fragments before the first fragment with a non full payload is received. This management is used to ensure that normal GPS operation doesn't corrupt RTCM data, and to recover from a unreliable transport delivery order. - */ -static inline uint8_t mavlink_msg_gps_rtcm_data_get_flags(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 0); -} - -/** - * @brief Get field len from gps_rtcm_data message - * - * @return [bytes] data length - */ -static inline uint8_t mavlink_msg_gps_rtcm_data_get_len(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 1); -} - -/** - * @brief Get field data from gps_rtcm_data message - * - * @return RTCM message (may be fragmented) - */ -static inline uint16_t mavlink_msg_gps_rtcm_data_get_data(const mavlink_message_t* msg, uint8_t *data) -{ - return _MAV_RETURN_uint8_t_array(msg, data, 180, 2); -} - -/** - * @brief Decode a gps_rtcm_data message into a struct - * - * @param msg The message to decode - * @param gps_rtcm_data C-struct to decode the message contents into - */ -static inline void mavlink_msg_gps_rtcm_data_decode(const mavlink_message_t* msg, mavlink_gps_rtcm_data_t* gps_rtcm_data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - gps_rtcm_data->flags = mavlink_msg_gps_rtcm_data_get_flags(msg); - gps_rtcm_data->len = mavlink_msg_gps_rtcm_data_get_len(msg); - mavlink_msg_gps_rtcm_data_get_data(msg, gps_rtcm_data->data); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_GPS_RTCM_DATA_LEN? msg->len : MAVLINK_MSG_ID_GPS_RTCM_DATA_LEN; - memset(gps_rtcm_data, 0, MAVLINK_MSG_ID_GPS_RTCM_DATA_LEN); - memcpy(gps_rtcm_data, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_gps_rtk.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_gps_rtk.h deleted file mode 100644 index 538b0db9..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_gps_rtk.h +++ /dev/null @@ -1,513 +0,0 @@ -#pragma once -// MESSAGE GPS_RTK PACKING - -#define MAVLINK_MSG_ID_GPS_RTK 127 - - -typedef struct __mavlink_gps_rtk_t { - uint32_t time_last_baseline_ms; /*< [ms] Time since boot of last baseline message received.*/ - uint32_t tow; /*< [ms] GPS Time of Week of last baseline*/ - int32_t baseline_a_mm; /*< [mm] Current baseline in ECEF x or NED north component.*/ - int32_t baseline_b_mm; /*< [mm] Current baseline in ECEF y or NED east component.*/ - int32_t baseline_c_mm; /*< [mm] Current baseline in ECEF z or NED down component.*/ - uint32_t accuracy; /*< Current estimate of baseline accuracy.*/ - int32_t iar_num_hypotheses; /*< Current number of integer ambiguity hypotheses.*/ - uint16_t wn; /*< GPS Week Number of last baseline*/ - uint8_t rtk_receiver_id; /*< Identification of connected RTK receiver.*/ - uint8_t rtk_health; /*< GPS-specific health report for RTK data.*/ - uint8_t rtk_rate; /*< [Hz] Rate of baseline messages being received by GPS*/ - uint8_t nsats; /*< Current number of sats used for RTK calculation.*/ - uint8_t baseline_coords_type; /*< Coordinate system of baseline*/ -} mavlink_gps_rtk_t; - -#define MAVLINK_MSG_ID_GPS_RTK_LEN 35 -#define MAVLINK_MSG_ID_GPS_RTK_MIN_LEN 35 -#define MAVLINK_MSG_ID_127_LEN 35 -#define MAVLINK_MSG_ID_127_MIN_LEN 35 - -#define MAVLINK_MSG_ID_GPS_RTK_CRC 25 -#define MAVLINK_MSG_ID_127_CRC 25 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_GPS_RTK { \ - 127, \ - "GPS_RTK", \ - 13, \ - { { "time_last_baseline_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_gps_rtk_t, time_last_baseline_ms) }, \ - { "rtk_receiver_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_gps_rtk_t, rtk_receiver_id) }, \ - { "wn", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_gps_rtk_t, wn) }, \ - { "tow", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_gps_rtk_t, tow) }, \ - { "rtk_health", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_gps_rtk_t, rtk_health) }, \ - { "rtk_rate", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_gps_rtk_t, rtk_rate) }, \ - { "nsats", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_gps_rtk_t, nsats) }, \ - { "baseline_coords_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_gps_rtk_t, baseline_coords_type) }, \ - { "baseline_a_mm", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_gps_rtk_t, baseline_a_mm) }, \ - { "baseline_b_mm", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_gps_rtk_t, baseline_b_mm) }, \ - { "baseline_c_mm", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_gps_rtk_t, baseline_c_mm) }, \ - { "accuracy", NULL, MAVLINK_TYPE_UINT32_T, 0, 20, offsetof(mavlink_gps_rtk_t, accuracy) }, \ - { "iar_num_hypotheses", NULL, MAVLINK_TYPE_INT32_T, 0, 24, offsetof(mavlink_gps_rtk_t, iar_num_hypotheses) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_GPS_RTK { \ - "GPS_RTK", \ - 13, \ - { { "time_last_baseline_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_gps_rtk_t, time_last_baseline_ms) }, \ - { "rtk_receiver_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_gps_rtk_t, rtk_receiver_id) }, \ - { "wn", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_gps_rtk_t, wn) }, \ - { "tow", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_gps_rtk_t, tow) }, \ - { "rtk_health", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_gps_rtk_t, rtk_health) }, \ - { "rtk_rate", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_gps_rtk_t, rtk_rate) }, \ - { "nsats", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_gps_rtk_t, nsats) }, \ - { "baseline_coords_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_gps_rtk_t, baseline_coords_type) }, \ - { "baseline_a_mm", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_gps_rtk_t, baseline_a_mm) }, \ - { "baseline_b_mm", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_gps_rtk_t, baseline_b_mm) }, \ - { "baseline_c_mm", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_gps_rtk_t, baseline_c_mm) }, \ - { "accuracy", NULL, MAVLINK_TYPE_UINT32_T, 0, 20, offsetof(mavlink_gps_rtk_t, accuracy) }, \ - { "iar_num_hypotheses", NULL, MAVLINK_TYPE_INT32_T, 0, 24, offsetof(mavlink_gps_rtk_t, iar_num_hypotheses) }, \ - } \ -} -#endif - -/** - * @brief Pack a gps_rtk message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param time_last_baseline_ms [ms] Time since boot of last baseline message received. - * @param rtk_receiver_id Identification of connected RTK receiver. - * @param wn GPS Week Number of last baseline - * @param tow [ms] GPS Time of Week of last baseline - * @param rtk_health GPS-specific health report for RTK data. - * @param rtk_rate [Hz] Rate of baseline messages being received by GPS - * @param nsats Current number of sats used for RTK calculation. - * @param baseline_coords_type Coordinate system of baseline - * @param baseline_a_mm [mm] Current baseline in ECEF x or NED north component. - * @param baseline_b_mm [mm] Current baseline in ECEF y or NED east component. - * @param baseline_c_mm [mm] Current baseline in ECEF z or NED down component. - * @param accuracy Current estimate of baseline accuracy. - * @param iar_num_hypotheses Current number of integer ambiguity hypotheses. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_gps_rtk_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint32_t time_last_baseline_ms, uint8_t rtk_receiver_id, uint16_t wn, uint32_t tow, uint8_t rtk_health, uint8_t rtk_rate, uint8_t nsats, uint8_t baseline_coords_type, int32_t baseline_a_mm, int32_t baseline_b_mm, int32_t baseline_c_mm, uint32_t accuracy, int32_t iar_num_hypotheses) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_GPS_RTK_LEN]; - _mav_put_uint32_t(buf, 0, time_last_baseline_ms); - _mav_put_uint32_t(buf, 4, tow); - _mav_put_int32_t(buf, 8, baseline_a_mm); - _mav_put_int32_t(buf, 12, baseline_b_mm); - _mav_put_int32_t(buf, 16, baseline_c_mm); - _mav_put_uint32_t(buf, 20, accuracy); - _mav_put_int32_t(buf, 24, iar_num_hypotheses); - _mav_put_uint16_t(buf, 28, wn); - _mav_put_uint8_t(buf, 30, rtk_receiver_id); - _mav_put_uint8_t(buf, 31, rtk_health); - _mav_put_uint8_t(buf, 32, rtk_rate); - _mav_put_uint8_t(buf, 33, nsats); - _mav_put_uint8_t(buf, 34, baseline_coords_type); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS_RTK_LEN); -#else - mavlink_gps_rtk_t packet; - packet.time_last_baseline_ms = time_last_baseline_ms; - packet.tow = tow; - packet.baseline_a_mm = baseline_a_mm; - packet.baseline_b_mm = baseline_b_mm; - packet.baseline_c_mm = baseline_c_mm; - packet.accuracy = accuracy; - packet.iar_num_hypotheses = iar_num_hypotheses; - packet.wn = wn; - packet.rtk_receiver_id = rtk_receiver_id; - packet.rtk_health = rtk_health; - packet.rtk_rate = rtk_rate; - packet.nsats = nsats; - packet.baseline_coords_type = baseline_coords_type; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS_RTK_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_GPS_RTK; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS_RTK_MIN_LEN, MAVLINK_MSG_ID_GPS_RTK_LEN, MAVLINK_MSG_ID_GPS_RTK_CRC); -} - -/** - * @brief Pack a gps_rtk message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_last_baseline_ms [ms] Time since boot of last baseline message received. - * @param rtk_receiver_id Identification of connected RTK receiver. - * @param wn GPS Week Number of last baseline - * @param tow [ms] GPS Time of Week of last baseline - * @param rtk_health GPS-specific health report for RTK data. - * @param rtk_rate [Hz] Rate of baseline messages being received by GPS - * @param nsats Current number of sats used for RTK calculation. - * @param baseline_coords_type Coordinate system of baseline - * @param baseline_a_mm [mm] Current baseline in ECEF x or NED north component. - * @param baseline_b_mm [mm] Current baseline in ECEF y or NED east component. - * @param baseline_c_mm [mm] Current baseline in ECEF z or NED down component. - * @param accuracy Current estimate of baseline accuracy. - * @param iar_num_hypotheses Current number of integer ambiguity hypotheses. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_gps_rtk_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint32_t time_last_baseline_ms,uint8_t rtk_receiver_id,uint16_t wn,uint32_t tow,uint8_t rtk_health,uint8_t rtk_rate,uint8_t nsats,uint8_t baseline_coords_type,int32_t baseline_a_mm,int32_t baseline_b_mm,int32_t baseline_c_mm,uint32_t accuracy,int32_t iar_num_hypotheses) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_GPS_RTK_LEN]; - _mav_put_uint32_t(buf, 0, time_last_baseline_ms); - _mav_put_uint32_t(buf, 4, tow); - _mav_put_int32_t(buf, 8, baseline_a_mm); - _mav_put_int32_t(buf, 12, baseline_b_mm); - _mav_put_int32_t(buf, 16, baseline_c_mm); - _mav_put_uint32_t(buf, 20, accuracy); - _mav_put_int32_t(buf, 24, iar_num_hypotheses); - _mav_put_uint16_t(buf, 28, wn); - _mav_put_uint8_t(buf, 30, rtk_receiver_id); - _mav_put_uint8_t(buf, 31, rtk_health); - _mav_put_uint8_t(buf, 32, rtk_rate); - _mav_put_uint8_t(buf, 33, nsats); - _mav_put_uint8_t(buf, 34, baseline_coords_type); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS_RTK_LEN); -#else - mavlink_gps_rtk_t packet; - packet.time_last_baseline_ms = time_last_baseline_ms; - packet.tow = tow; - packet.baseline_a_mm = baseline_a_mm; - packet.baseline_b_mm = baseline_b_mm; - packet.baseline_c_mm = baseline_c_mm; - packet.accuracy = accuracy; - packet.iar_num_hypotheses = iar_num_hypotheses; - packet.wn = wn; - packet.rtk_receiver_id = rtk_receiver_id; - packet.rtk_health = rtk_health; - packet.rtk_rate = rtk_rate; - packet.nsats = nsats; - packet.baseline_coords_type = baseline_coords_type; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS_RTK_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_GPS_RTK; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GPS_RTK_MIN_LEN, MAVLINK_MSG_ID_GPS_RTK_LEN, MAVLINK_MSG_ID_GPS_RTK_CRC); -} - -/** - * @brief Encode a gps_rtk struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param gps_rtk C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_gps_rtk_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gps_rtk_t* gps_rtk) -{ - return mavlink_msg_gps_rtk_pack(system_id, component_id, msg, gps_rtk->time_last_baseline_ms, gps_rtk->rtk_receiver_id, gps_rtk->wn, gps_rtk->tow, gps_rtk->rtk_health, gps_rtk->rtk_rate, gps_rtk->nsats, gps_rtk->baseline_coords_type, gps_rtk->baseline_a_mm, gps_rtk->baseline_b_mm, gps_rtk->baseline_c_mm, gps_rtk->accuracy, gps_rtk->iar_num_hypotheses); -} - -/** - * @brief Encode a gps_rtk struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param gps_rtk C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_gps_rtk_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_gps_rtk_t* gps_rtk) -{ - return mavlink_msg_gps_rtk_pack_chan(system_id, component_id, chan, msg, gps_rtk->time_last_baseline_ms, gps_rtk->rtk_receiver_id, gps_rtk->wn, gps_rtk->tow, gps_rtk->rtk_health, gps_rtk->rtk_rate, gps_rtk->nsats, gps_rtk->baseline_coords_type, gps_rtk->baseline_a_mm, gps_rtk->baseline_b_mm, gps_rtk->baseline_c_mm, gps_rtk->accuracy, gps_rtk->iar_num_hypotheses); -} - -/** - * @brief Send a gps_rtk message - * @param chan MAVLink channel to send the message - * - * @param time_last_baseline_ms [ms] Time since boot of last baseline message received. - * @param rtk_receiver_id Identification of connected RTK receiver. - * @param wn GPS Week Number of last baseline - * @param tow [ms] GPS Time of Week of last baseline - * @param rtk_health GPS-specific health report for RTK data. - * @param rtk_rate [Hz] Rate of baseline messages being received by GPS - * @param nsats Current number of sats used for RTK calculation. - * @param baseline_coords_type Coordinate system of baseline - * @param baseline_a_mm [mm] Current baseline in ECEF x or NED north component. - * @param baseline_b_mm [mm] Current baseline in ECEF y or NED east component. - * @param baseline_c_mm [mm] Current baseline in ECEF z or NED down component. - * @param accuracy Current estimate of baseline accuracy. - * @param iar_num_hypotheses Current number of integer ambiguity hypotheses. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_gps_rtk_send(mavlink_channel_t chan, uint32_t time_last_baseline_ms, uint8_t rtk_receiver_id, uint16_t wn, uint32_t tow, uint8_t rtk_health, uint8_t rtk_rate, uint8_t nsats, uint8_t baseline_coords_type, int32_t baseline_a_mm, int32_t baseline_b_mm, int32_t baseline_c_mm, uint32_t accuracy, int32_t iar_num_hypotheses) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_GPS_RTK_LEN]; - _mav_put_uint32_t(buf, 0, time_last_baseline_ms); - _mav_put_uint32_t(buf, 4, tow); - _mav_put_int32_t(buf, 8, baseline_a_mm); - _mav_put_int32_t(buf, 12, baseline_b_mm); - _mav_put_int32_t(buf, 16, baseline_c_mm); - _mav_put_uint32_t(buf, 20, accuracy); - _mav_put_int32_t(buf, 24, iar_num_hypotheses); - _mav_put_uint16_t(buf, 28, wn); - _mav_put_uint8_t(buf, 30, rtk_receiver_id); - _mav_put_uint8_t(buf, 31, rtk_health); - _mav_put_uint8_t(buf, 32, rtk_rate); - _mav_put_uint8_t(buf, 33, nsats); - _mav_put_uint8_t(buf, 34, baseline_coords_type); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RTK, buf, MAVLINK_MSG_ID_GPS_RTK_MIN_LEN, MAVLINK_MSG_ID_GPS_RTK_LEN, MAVLINK_MSG_ID_GPS_RTK_CRC); -#else - mavlink_gps_rtk_t packet; - packet.time_last_baseline_ms = time_last_baseline_ms; - packet.tow = tow; - packet.baseline_a_mm = baseline_a_mm; - packet.baseline_b_mm = baseline_b_mm; - packet.baseline_c_mm = baseline_c_mm; - packet.accuracy = accuracy; - packet.iar_num_hypotheses = iar_num_hypotheses; - packet.wn = wn; - packet.rtk_receiver_id = rtk_receiver_id; - packet.rtk_health = rtk_health; - packet.rtk_rate = rtk_rate; - packet.nsats = nsats; - packet.baseline_coords_type = baseline_coords_type; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RTK, (const char *)&packet, MAVLINK_MSG_ID_GPS_RTK_MIN_LEN, MAVLINK_MSG_ID_GPS_RTK_LEN, MAVLINK_MSG_ID_GPS_RTK_CRC); -#endif -} - -/** - * @brief Send a gps_rtk message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_gps_rtk_send_struct(mavlink_channel_t chan, const mavlink_gps_rtk_t* gps_rtk) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_gps_rtk_send(chan, gps_rtk->time_last_baseline_ms, gps_rtk->rtk_receiver_id, gps_rtk->wn, gps_rtk->tow, gps_rtk->rtk_health, gps_rtk->rtk_rate, gps_rtk->nsats, gps_rtk->baseline_coords_type, gps_rtk->baseline_a_mm, gps_rtk->baseline_b_mm, gps_rtk->baseline_c_mm, gps_rtk->accuracy, gps_rtk->iar_num_hypotheses); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RTK, (const char *)gps_rtk, MAVLINK_MSG_ID_GPS_RTK_MIN_LEN, MAVLINK_MSG_ID_GPS_RTK_LEN, MAVLINK_MSG_ID_GPS_RTK_CRC); -#endif -} - -#if MAVLINK_MSG_ID_GPS_RTK_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_gps_rtk_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_last_baseline_ms, uint8_t rtk_receiver_id, uint16_t wn, uint32_t tow, uint8_t rtk_health, uint8_t rtk_rate, uint8_t nsats, uint8_t baseline_coords_type, int32_t baseline_a_mm, int32_t baseline_b_mm, int32_t baseline_c_mm, uint32_t accuracy, int32_t iar_num_hypotheses) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, time_last_baseline_ms); - _mav_put_uint32_t(buf, 4, tow); - _mav_put_int32_t(buf, 8, baseline_a_mm); - _mav_put_int32_t(buf, 12, baseline_b_mm); - _mav_put_int32_t(buf, 16, baseline_c_mm); - _mav_put_uint32_t(buf, 20, accuracy); - _mav_put_int32_t(buf, 24, iar_num_hypotheses); - _mav_put_uint16_t(buf, 28, wn); - _mav_put_uint8_t(buf, 30, rtk_receiver_id); - _mav_put_uint8_t(buf, 31, rtk_health); - _mav_put_uint8_t(buf, 32, rtk_rate); - _mav_put_uint8_t(buf, 33, nsats); - _mav_put_uint8_t(buf, 34, baseline_coords_type); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RTK, buf, MAVLINK_MSG_ID_GPS_RTK_MIN_LEN, MAVLINK_MSG_ID_GPS_RTK_LEN, MAVLINK_MSG_ID_GPS_RTK_CRC); -#else - mavlink_gps_rtk_t *packet = (mavlink_gps_rtk_t *)msgbuf; - packet->time_last_baseline_ms = time_last_baseline_ms; - packet->tow = tow; - packet->baseline_a_mm = baseline_a_mm; - packet->baseline_b_mm = baseline_b_mm; - packet->baseline_c_mm = baseline_c_mm; - packet->accuracy = accuracy; - packet->iar_num_hypotheses = iar_num_hypotheses; - packet->wn = wn; - packet->rtk_receiver_id = rtk_receiver_id; - packet->rtk_health = rtk_health; - packet->rtk_rate = rtk_rate; - packet->nsats = nsats; - packet->baseline_coords_type = baseline_coords_type; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RTK, (const char *)packet, MAVLINK_MSG_ID_GPS_RTK_MIN_LEN, MAVLINK_MSG_ID_GPS_RTK_LEN, MAVLINK_MSG_ID_GPS_RTK_CRC); -#endif -} -#endif - -#endif - -// MESSAGE GPS_RTK UNPACKING - - -/** - * @brief Get field time_last_baseline_ms from gps_rtk message - * - * @return [ms] Time since boot of last baseline message received. - */ -static inline uint32_t mavlink_msg_gps_rtk_get_time_last_baseline_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field rtk_receiver_id from gps_rtk message - * - * @return Identification of connected RTK receiver. - */ -static inline uint8_t mavlink_msg_gps_rtk_get_rtk_receiver_id(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 30); -} - -/** - * @brief Get field wn from gps_rtk message - * - * @return GPS Week Number of last baseline - */ -static inline uint16_t mavlink_msg_gps_rtk_get_wn(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 28); -} - -/** - * @brief Get field tow from gps_rtk message - * - * @return [ms] GPS Time of Week of last baseline - */ -static inline uint32_t mavlink_msg_gps_rtk_get_tow(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 4); -} - -/** - * @brief Get field rtk_health from gps_rtk message - * - * @return GPS-specific health report for RTK data. - */ -static inline uint8_t mavlink_msg_gps_rtk_get_rtk_health(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 31); -} - -/** - * @brief Get field rtk_rate from gps_rtk message - * - * @return [Hz] Rate of baseline messages being received by GPS - */ -static inline uint8_t mavlink_msg_gps_rtk_get_rtk_rate(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 32); -} - -/** - * @brief Get field nsats from gps_rtk message - * - * @return Current number of sats used for RTK calculation. - */ -static inline uint8_t mavlink_msg_gps_rtk_get_nsats(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 33); -} - -/** - * @brief Get field baseline_coords_type from gps_rtk message - * - * @return Coordinate system of baseline - */ -static inline uint8_t mavlink_msg_gps_rtk_get_baseline_coords_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 34); -} - -/** - * @brief Get field baseline_a_mm from gps_rtk message - * - * @return [mm] Current baseline in ECEF x or NED north component. - */ -static inline int32_t mavlink_msg_gps_rtk_get_baseline_a_mm(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 8); -} - -/** - * @brief Get field baseline_b_mm from gps_rtk message - * - * @return [mm] Current baseline in ECEF y or NED east component. - */ -static inline int32_t mavlink_msg_gps_rtk_get_baseline_b_mm(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 12); -} - -/** - * @brief Get field baseline_c_mm from gps_rtk message - * - * @return [mm] Current baseline in ECEF z or NED down component. - */ -static inline int32_t mavlink_msg_gps_rtk_get_baseline_c_mm(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 16); -} - -/** - * @brief Get field accuracy from gps_rtk message - * - * @return Current estimate of baseline accuracy. - */ -static inline uint32_t mavlink_msg_gps_rtk_get_accuracy(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 20); -} - -/** - * @brief Get field iar_num_hypotheses from gps_rtk message - * - * @return Current number of integer ambiguity hypotheses. - */ -static inline int32_t mavlink_msg_gps_rtk_get_iar_num_hypotheses(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 24); -} - -/** - * @brief Decode a gps_rtk message into a struct - * - * @param msg The message to decode - * @param gps_rtk C-struct to decode the message contents into - */ -static inline void mavlink_msg_gps_rtk_decode(const mavlink_message_t* msg, mavlink_gps_rtk_t* gps_rtk) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - gps_rtk->time_last_baseline_ms = mavlink_msg_gps_rtk_get_time_last_baseline_ms(msg); - gps_rtk->tow = mavlink_msg_gps_rtk_get_tow(msg); - gps_rtk->baseline_a_mm = mavlink_msg_gps_rtk_get_baseline_a_mm(msg); - gps_rtk->baseline_b_mm = mavlink_msg_gps_rtk_get_baseline_b_mm(msg); - gps_rtk->baseline_c_mm = mavlink_msg_gps_rtk_get_baseline_c_mm(msg); - gps_rtk->accuracy = mavlink_msg_gps_rtk_get_accuracy(msg); - gps_rtk->iar_num_hypotheses = mavlink_msg_gps_rtk_get_iar_num_hypotheses(msg); - gps_rtk->wn = mavlink_msg_gps_rtk_get_wn(msg); - gps_rtk->rtk_receiver_id = mavlink_msg_gps_rtk_get_rtk_receiver_id(msg); - gps_rtk->rtk_health = mavlink_msg_gps_rtk_get_rtk_health(msg); - gps_rtk->rtk_rate = mavlink_msg_gps_rtk_get_rtk_rate(msg); - gps_rtk->nsats = mavlink_msg_gps_rtk_get_nsats(msg); - gps_rtk->baseline_coords_type = mavlink_msg_gps_rtk_get_baseline_coords_type(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_GPS_RTK_LEN? msg->len : MAVLINK_MSG_ID_GPS_RTK_LEN; - memset(gps_rtk, 0, MAVLINK_MSG_ID_GPS_RTK_LEN); - memcpy(gps_rtk, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_gps_status.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_gps_status.h deleted file mode 100644 index 65273a5c..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_gps_status.h +++ /dev/null @@ -1,334 +0,0 @@ -#pragma once -// MESSAGE GPS_STATUS PACKING - -#define MAVLINK_MSG_ID_GPS_STATUS 25 - - -typedef struct __mavlink_gps_status_t { - uint8_t satellites_visible; /*< Number of satellites visible*/ - uint8_t satellite_prn[20]; /*< Global satellite ID*/ - uint8_t satellite_used[20]; /*< 0: Satellite not used, 1: used for localization*/ - uint8_t satellite_elevation[20]; /*< [deg] Elevation (0: right on top of receiver, 90: on the horizon) of satellite*/ - uint8_t satellite_azimuth[20]; /*< [deg] Direction of satellite, 0: 0 deg, 255: 360 deg.*/ - uint8_t satellite_snr[20]; /*< [dB] Signal to noise ratio of satellite*/ -} mavlink_gps_status_t; - -#define MAVLINK_MSG_ID_GPS_STATUS_LEN 101 -#define MAVLINK_MSG_ID_GPS_STATUS_MIN_LEN 101 -#define MAVLINK_MSG_ID_25_LEN 101 -#define MAVLINK_MSG_ID_25_MIN_LEN 101 - -#define MAVLINK_MSG_ID_GPS_STATUS_CRC 23 -#define MAVLINK_MSG_ID_25_CRC 23 - -#define MAVLINK_MSG_GPS_STATUS_FIELD_SATELLITE_PRN_LEN 20 -#define MAVLINK_MSG_GPS_STATUS_FIELD_SATELLITE_USED_LEN 20 -#define MAVLINK_MSG_GPS_STATUS_FIELD_SATELLITE_ELEVATION_LEN 20 -#define MAVLINK_MSG_GPS_STATUS_FIELD_SATELLITE_AZIMUTH_LEN 20 -#define MAVLINK_MSG_GPS_STATUS_FIELD_SATELLITE_SNR_LEN 20 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_GPS_STATUS { \ - 25, \ - "GPS_STATUS", \ - 6, \ - { { "satellites_visible", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_gps_status_t, satellites_visible) }, \ - { "satellite_prn", NULL, MAVLINK_TYPE_UINT8_T, 20, 1, offsetof(mavlink_gps_status_t, satellite_prn) }, \ - { "satellite_used", NULL, MAVLINK_TYPE_UINT8_T, 20, 21, offsetof(mavlink_gps_status_t, satellite_used) }, \ - { "satellite_elevation", NULL, MAVLINK_TYPE_UINT8_T, 20, 41, offsetof(mavlink_gps_status_t, satellite_elevation) }, \ - { "satellite_azimuth", NULL, MAVLINK_TYPE_UINT8_T, 20, 61, offsetof(mavlink_gps_status_t, satellite_azimuth) }, \ - { "satellite_snr", NULL, MAVLINK_TYPE_UINT8_T, 20, 81, offsetof(mavlink_gps_status_t, satellite_snr) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_GPS_STATUS { \ - "GPS_STATUS", \ - 6, \ - { { "satellites_visible", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_gps_status_t, satellites_visible) }, \ - { "satellite_prn", NULL, MAVLINK_TYPE_UINT8_T, 20, 1, offsetof(mavlink_gps_status_t, satellite_prn) }, \ - { "satellite_used", NULL, MAVLINK_TYPE_UINT8_T, 20, 21, offsetof(mavlink_gps_status_t, satellite_used) }, \ - { "satellite_elevation", NULL, MAVLINK_TYPE_UINT8_T, 20, 41, offsetof(mavlink_gps_status_t, satellite_elevation) }, \ - { "satellite_azimuth", NULL, MAVLINK_TYPE_UINT8_T, 20, 61, offsetof(mavlink_gps_status_t, satellite_azimuth) }, \ - { "satellite_snr", NULL, MAVLINK_TYPE_UINT8_T, 20, 81, offsetof(mavlink_gps_status_t, satellite_snr) }, \ - } \ -} -#endif - -/** - * @brief Pack a gps_status message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param satellites_visible Number of satellites visible - * @param satellite_prn Global satellite ID - * @param satellite_used 0: Satellite not used, 1: used for localization - * @param satellite_elevation [deg] Elevation (0: right on top of receiver, 90: on the horizon) of satellite - * @param satellite_azimuth [deg] Direction of satellite, 0: 0 deg, 255: 360 deg. - * @param satellite_snr [dB] Signal to noise ratio of satellite - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_gps_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t satellites_visible, const uint8_t *satellite_prn, const uint8_t *satellite_used, const uint8_t *satellite_elevation, const uint8_t *satellite_azimuth, const uint8_t *satellite_snr) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_GPS_STATUS_LEN]; - _mav_put_uint8_t(buf, 0, satellites_visible); - _mav_put_uint8_t_array(buf, 1, satellite_prn, 20); - _mav_put_uint8_t_array(buf, 21, satellite_used, 20); - _mav_put_uint8_t_array(buf, 41, satellite_elevation, 20); - _mav_put_uint8_t_array(buf, 61, satellite_azimuth, 20); - _mav_put_uint8_t_array(buf, 81, satellite_snr, 20); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS_STATUS_LEN); -#else - mavlink_gps_status_t packet; - packet.satellites_visible = satellites_visible; - mav_array_memcpy(packet.satellite_prn, satellite_prn, sizeof(uint8_t)*20); - mav_array_memcpy(packet.satellite_used, satellite_used, sizeof(uint8_t)*20); - mav_array_memcpy(packet.satellite_elevation, satellite_elevation, sizeof(uint8_t)*20); - mav_array_memcpy(packet.satellite_azimuth, satellite_azimuth, sizeof(uint8_t)*20); - mav_array_memcpy(packet.satellite_snr, satellite_snr, sizeof(uint8_t)*20); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS_STATUS_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_GPS_STATUS; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS_STATUS_MIN_LEN, MAVLINK_MSG_ID_GPS_STATUS_LEN, MAVLINK_MSG_ID_GPS_STATUS_CRC); -} - -/** - * @brief Pack a gps_status message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param satellites_visible Number of satellites visible - * @param satellite_prn Global satellite ID - * @param satellite_used 0: Satellite not used, 1: used for localization - * @param satellite_elevation [deg] Elevation (0: right on top of receiver, 90: on the horizon) of satellite - * @param satellite_azimuth [deg] Direction of satellite, 0: 0 deg, 255: 360 deg. - * @param satellite_snr [dB] Signal to noise ratio of satellite - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_gps_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t satellites_visible,const uint8_t *satellite_prn,const uint8_t *satellite_used,const uint8_t *satellite_elevation,const uint8_t *satellite_azimuth,const uint8_t *satellite_snr) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_GPS_STATUS_LEN]; - _mav_put_uint8_t(buf, 0, satellites_visible); - _mav_put_uint8_t_array(buf, 1, satellite_prn, 20); - _mav_put_uint8_t_array(buf, 21, satellite_used, 20); - _mav_put_uint8_t_array(buf, 41, satellite_elevation, 20); - _mav_put_uint8_t_array(buf, 61, satellite_azimuth, 20); - _mav_put_uint8_t_array(buf, 81, satellite_snr, 20); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS_STATUS_LEN); -#else - mavlink_gps_status_t packet; - packet.satellites_visible = satellites_visible; - mav_array_memcpy(packet.satellite_prn, satellite_prn, sizeof(uint8_t)*20); - mav_array_memcpy(packet.satellite_used, satellite_used, sizeof(uint8_t)*20); - mav_array_memcpy(packet.satellite_elevation, satellite_elevation, sizeof(uint8_t)*20); - mav_array_memcpy(packet.satellite_azimuth, satellite_azimuth, sizeof(uint8_t)*20); - mav_array_memcpy(packet.satellite_snr, satellite_snr, sizeof(uint8_t)*20); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS_STATUS_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_GPS_STATUS; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GPS_STATUS_MIN_LEN, MAVLINK_MSG_ID_GPS_STATUS_LEN, MAVLINK_MSG_ID_GPS_STATUS_CRC); -} - -/** - * @brief Encode a gps_status struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param gps_status C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_gps_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gps_status_t* gps_status) -{ - return mavlink_msg_gps_status_pack(system_id, component_id, msg, gps_status->satellites_visible, gps_status->satellite_prn, gps_status->satellite_used, gps_status->satellite_elevation, gps_status->satellite_azimuth, gps_status->satellite_snr); -} - -/** - * @brief Encode a gps_status struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param gps_status C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_gps_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_gps_status_t* gps_status) -{ - return mavlink_msg_gps_status_pack_chan(system_id, component_id, chan, msg, gps_status->satellites_visible, gps_status->satellite_prn, gps_status->satellite_used, gps_status->satellite_elevation, gps_status->satellite_azimuth, gps_status->satellite_snr); -} - -/** - * @brief Send a gps_status message - * @param chan MAVLink channel to send the message - * - * @param satellites_visible Number of satellites visible - * @param satellite_prn Global satellite ID - * @param satellite_used 0: Satellite not used, 1: used for localization - * @param satellite_elevation [deg] Elevation (0: right on top of receiver, 90: on the horizon) of satellite - * @param satellite_azimuth [deg] Direction of satellite, 0: 0 deg, 255: 360 deg. - * @param satellite_snr [dB] Signal to noise ratio of satellite - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_gps_status_send(mavlink_channel_t chan, uint8_t satellites_visible, const uint8_t *satellite_prn, const uint8_t *satellite_used, const uint8_t *satellite_elevation, const uint8_t *satellite_azimuth, const uint8_t *satellite_snr) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_GPS_STATUS_LEN]; - _mav_put_uint8_t(buf, 0, satellites_visible); - _mav_put_uint8_t_array(buf, 1, satellite_prn, 20); - _mav_put_uint8_t_array(buf, 21, satellite_used, 20); - _mav_put_uint8_t_array(buf, 41, satellite_elevation, 20); - _mav_put_uint8_t_array(buf, 61, satellite_azimuth, 20); - _mav_put_uint8_t_array(buf, 81, satellite_snr, 20); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_STATUS, buf, MAVLINK_MSG_ID_GPS_STATUS_MIN_LEN, MAVLINK_MSG_ID_GPS_STATUS_LEN, MAVLINK_MSG_ID_GPS_STATUS_CRC); -#else - mavlink_gps_status_t packet; - packet.satellites_visible = satellites_visible; - mav_array_memcpy(packet.satellite_prn, satellite_prn, sizeof(uint8_t)*20); - mav_array_memcpy(packet.satellite_used, satellite_used, sizeof(uint8_t)*20); - mav_array_memcpy(packet.satellite_elevation, satellite_elevation, sizeof(uint8_t)*20); - mav_array_memcpy(packet.satellite_azimuth, satellite_azimuth, sizeof(uint8_t)*20); - mav_array_memcpy(packet.satellite_snr, satellite_snr, sizeof(uint8_t)*20); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_STATUS, (const char *)&packet, MAVLINK_MSG_ID_GPS_STATUS_MIN_LEN, MAVLINK_MSG_ID_GPS_STATUS_LEN, MAVLINK_MSG_ID_GPS_STATUS_CRC); -#endif -} - -/** - * @brief Send a gps_status message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_gps_status_send_struct(mavlink_channel_t chan, const mavlink_gps_status_t* gps_status) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_gps_status_send(chan, gps_status->satellites_visible, gps_status->satellite_prn, gps_status->satellite_used, gps_status->satellite_elevation, gps_status->satellite_azimuth, gps_status->satellite_snr); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_STATUS, (const char *)gps_status, MAVLINK_MSG_ID_GPS_STATUS_MIN_LEN, MAVLINK_MSG_ID_GPS_STATUS_LEN, MAVLINK_MSG_ID_GPS_STATUS_CRC); -#endif -} - -#if MAVLINK_MSG_ID_GPS_STATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_gps_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t satellites_visible, const uint8_t *satellite_prn, const uint8_t *satellite_used, const uint8_t *satellite_elevation, const uint8_t *satellite_azimuth, const uint8_t *satellite_snr) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint8_t(buf, 0, satellites_visible); - _mav_put_uint8_t_array(buf, 1, satellite_prn, 20); - _mav_put_uint8_t_array(buf, 21, satellite_used, 20); - _mav_put_uint8_t_array(buf, 41, satellite_elevation, 20); - _mav_put_uint8_t_array(buf, 61, satellite_azimuth, 20); - _mav_put_uint8_t_array(buf, 81, satellite_snr, 20); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_STATUS, buf, MAVLINK_MSG_ID_GPS_STATUS_MIN_LEN, MAVLINK_MSG_ID_GPS_STATUS_LEN, MAVLINK_MSG_ID_GPS_STATUS_CRC); -#else - mavlink_gps_status_t *packet = (mavlink_gps_status_t *)msgbuf; - packet->satellites_visible = satellites_visible; - mav_array_memcpy(packet->satellite_prn, satellite_prn, sizeof(uint8_t)*20); - mav_array_memcpy(packet->satellite_used, satellite_used, sizeof(uint8_t)*20); - mav_array_memcpy(packet->satellite_elevation, satellite_elevation, sizeof(uint8_t)*20); - mav_array_memcpy(packet->satellite_azimuth, satellite_azimuth, sizeof(uint8_t)*20); - mav_array_memcpy(packet->satellite_snr, satellite_snr, sizeof(uint8_t)*20); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_STATUS, (const char *)packet, MAVLINK_MSG_ID_GPS_STATUS_MIN_LEN, MAVLINK_MSG_ID_GPS_STATUS_LEN, MAVLINK_MSG_ID_GPS_STATUS_CRC); -#endif -} -#endif - -#endif - -// MESSAGE GPS_STATUS UNPACKING - - -/** - * @brief Get field satellites_visible from gps_status message - * - * @return Number of satellites visible - */ -static inline uint8_t mavlink_msg_gps_status_get_satellites_visible(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 0); -} - -/** - * @brief Get field satellite_prn from gps_status message - * - * @return Global satellite ID - */ -static inline uint16_t mavlink_msg_gps_status_get_satellite_prn(const mavlink_message_t* msg, uint8_t *satellite_prn) -{ - return _MAV_RETURN_uint8_t_array(msg, satellite_prn, 20, 1); -} - -/** - * @brief Get field satellite_used from gps_status message - * - * @return 0: Satellite not used, 1: used for localization - */ -static inline uint16_t mavlink_msg_gps_status_get_satellite_used(const mavlink_message_t* msg, uint8_t *satellite_used) -{ - return _MAV_RETURN_uint8_t_array(msg, satellite_used, 20, 21); -} - -/** - * @brief Get field satellite_elevation from gps_status message - * - * @return [deg] Elevation (0: right on top of receiver, 90: on the horizon) of satellite - */ -static inline uint16_t mavlink_msg_gps_status_get_satellite_elevation(const mavlink_message_t* msg, uint8_t *satellite_elevation) -{ - return _MAV_RETURN_uint8_t_array(msg, satellite_elevation, 20, 41); -} - -/** - * @brief Get field satellite_azimuth from gps_status message - * - * @return [deg] Direction of satellite, 0: 0 deg, 255: 360 deg. - */ -static inline uint16_t mavlink_msg_gps_status_get_satellite_azimuth(const mavlink_message_t* msg, uint8_t *satellite_azimuth) -{ - return _MAV_RETURN_uint8_t_array(msg, satellite_azimuth, 20, 61); -} - -/** - * @brief Get field satellite_snr from gps_status message - * - * @return [dB] Signal to noise ratio of satellite - */ -static inline uint16_t mavlink_msg_gps_status_get_satellite_snr(const mavlink_message_t* msg, uint8_t *satellite_snr) -{ - return _MAV_RETURN_uint8_t_array(msg, satellite_snr, 20, 81); -} - -/** - * @brief Decode a gps_status message into a struct - * - * @param msg The message to decode - * @param gps_status C-struct to decode the message contents into - */ -static inline void mavlink_msg_gps_status_decode(const mavlink_message_t* msg, mavlink_gps_status_t* gps_status) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - gps_status->satellites_visible = mavlink_msg_gps_status_get_satellites_visible(msg); - mavlink_msg_gps_status_get_satellite_prn(msg, gps_status->satellite_prn); - mavlink_msg_gps_status_get_satellite_used(msg, gps_status->satellite_used); - mavlink_msg_gps_status_get_satellite_elevation(msg, gps_status->satellite_elevation); - mavlink_msg_gps_status_get_satellite_azimuth(msg, gps_status->satellite_azimuth); - mavlink_msg_gps_status_get_satellite_snr(msg, gps_status->satellite_snr); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_GPS_STATUS_LEN? msg->len : MAVLINK_MSG_ID_GPS_STATUS_LEN; - memset(gps_status, 0, MAVLINK_MSG_ID_GPS_STATUS_LEN); - memcpy(gps_status, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_high_latency.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_high_latency.h deleted file mode 100644 index 29ae264d..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_high_latency.h +++ /dev/null @@ -1,788 +0,0 @@ -#pragma once -// MESSAGE HIGH_LATENCY PACKING - -#define MAVLINK_MSG_ID_HIGH_LATENCY 234 - - -typedef struct __mavlink_high_latency_t { - uint32_t custom_mode; /*< A bitfield for use for autopilot-specific flags.*/ - int32_t latitude; /*< [degE7] Latitude*/ - int32_t longitude; /*< [degE7] Longitude*/ - int16_t roll; /*< [cdeg] roll*/ - int16_t pitch; /*< [cdeg] pitch*/ - uint16_t heading; /*< [cdeg] heading*/ - int16_t heading_sp; /*< [cdeg] heading setpoint*/ - int16_t altitude_amsl; /*< [m] Altitude above mean sea level*/ - int16_t altitude_sp; /*< [m] Altitude setpoint relative to the home position*/ - uint16_t wp_distance; /*< [m] distance to target*/ - uint8_t base_mode; /*< Bitmap of enabled system modes.*/ - uint8_t landed_state; /*< The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown.*/ - int8_t throttle; /*< [%] throttle (percentage)*/ - uint8_t airspeed; /*< [m/s] airspeed*/ - uint8_t airspeed_sp; /*< [m/s] airspeed setpoint*/ - uint8_t groundspeed; /*< [m/s] groundspeed*/ - int8_t climb_rate; /*< [m/s] climb rate*/ - uint8_t gps_nsat; /*< Number of satellites visible. If unknown, set to UINT8_MAX*/ - uint8_t gps_fix_type; /*< GPS Fix type.*/ - uint8_t battery_remaining; /*< [%] Remaining battery (percentage)*/ - int8_t temperature; /*< [degC] Autopilot temperature (degrees C)*/ - int8_t temperature_air; /*< [degC] Air temperature (degrees C) from airspeed sensor*/ - uint8_t failsafe; /*< failsafe (each bit represents a failsafe where 0=ok, 1=failsafe active (bit0:RC, bit1:batt, bit2:GPS, bit3:GCS, bit4:fence)*/ - uint8_t wp_num; /*< current waypoint number*/ -} mavlink_high_latency_t; - -#define MAVLINK_MSG_ID_HIGH_LATENCY_LEN 40 -#define MAVLINK_MSG_ID_HIGH_LATENCY_MIN_LEN 40 -#define MAVLINK_MSG_ID_234_LEN 40 -#define MAVLINK_MSG_ID_234_MIN_LEN 40 - -#define MAVLINK_MSG_ID_HIGH_LATENCY_CRC 150 -#define MAVLINK_MSG_ID_234_CRC 150 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_HIGH_LATENCY { \ - 234, \ - "HIGH_LATENCY", \ - 24, \ - { { "base_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 26, offsetof(mavlink_high_latency_t, base_mode) }, \ - { "custom_mode", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_high_latency_t, custom_mode) }, \ - { "landed_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 27, offsetof(mavlink_high_latency_t, landed_state) }, \ - { "roll", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_high_latency_t, roll) }, \ - { "pitch", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_high_latency_t, pitch) }, \ - { "heading", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_high_latency_t, heading) }, \ - { "throttle", NULL, MAVLINK_TYPE_INT8_T, 0, 28, offsetof(mavlink_high_latency_t, throttle) }, \ - { "heading_sp", NULL, MAVLINK_TYPE_INT16_T, 0, 18, offsetof(mavlink_high_latency_t, heading_sp) }, \ - { "latitude", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_high_latency_t, latitude) }, \ - { "longitude", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_high_latency_t, longitude) }, \ - { "altitude_amsl", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_high_latency_t, altitude_amsl) }, \ - { "altitude_sp", NULL, MAVLINK_TYPE_INT16_T, 0, 22, offsetof(mavlink_high_latency_t, altitude_sp) }, \ - { "airspeed", NULL, MAVLINK_TYPE_UINT8_T, 0, 29, offsetof(mavlink_high_latency_t, airspeed) }, \ - { "airspeed_sp", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_high_latency_t, airspeed_sp) }, \ - { "groundspeed", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_high_latency_t, groundspeed) }, \ - { "climb_rate", NULL, MAVLINK_TYPE_INT8_T, 0, 32, offsetof(mavlink_high_latency_t, climb_rate) }, \ - { "gps_nsat", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_high_latency_t, gps_nsat) }, \ - { "gps_fix_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_high_latency_t, gps_fix_type) }, \ - { "battery_remaining", NULL, MAVLINK_TYPE_UINT8_T, 0, 35, offsetof(mavlink_high_latency_t, battery_remaining) }, \ - { "temperature", NULL, MAVLINK_TYPE_INT8_T, 0, 36, offsetof(mavlink_high_latency_t, temperature) }, \ - { "temperature_air", NULL, MAVLINK_TYPE_INT8_T, 0, 37, offsetof(mavlink_high_latency_t, temperature_air) }, \ - { "failsafe", NULL, MAVLINK_TYPE_UINT8_T, 0, 38, offsetof(mavlink_high_latency_t, failsafe) }, \ - { "wp_num", NULL, MAVLINK_TYPE_UINT8_T, 0, 39, offsetof(mavlink_high_latency_t, wp_num) }, \ - { "wp_distance", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_high_latency_t, wp_distance) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_HIGH_LATENCY { \ - "HIGH_LATENCY", \ - 24, \ - { { "base_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 26, offsetof(mavlink_high_latency_t, base_mode) }, \ - { "custom_mode", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_high_latency_t, custom_mode) }, \ - { "landed_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 27, offsetof(mavlink_high_latency_t, landed_state) }, \ - { "roll", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_high_latency_t, roll) }, \ - { "pitch", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_high_latency_t, pitch) }, \ - { "heading", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_high_latency_t, heading) }, \ - { "throttle", NULL, MAVLINK_TYPE_INT8_T, 0, 28, offsetof(mavlink_high_latency_t, throttle) }, \ - { "heading_sp", NULL, MAVLINK_TYPE_INT16_T, 0, 18, offsetof(mavlink_high_latency_t, heading_sp) }, \ - { "latitude", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_high_latency_t, latitude) }, \ - { "longitude", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_high_latency_t, longitude) }, \ - { "altitude_amsl", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_high_latency_t, altitude_amsl) }, \ - { "altitude_sp", NULL, MAVLINK_TYPE_INT16_T, 0, 22, offsetof(mavlink_high_latency_t, altitude_sp) }, \ - { "airspeed", NULL, MAVLINK_TYPE_UINT8_T, 0, 29, offsetof(mavlink_high_latency_t, airspeed) }, \ - { "airspeed_sp", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_high_latency_t, airspeed_sp) }, \ - { "groundspeed", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_high_latency_t, groundspeed) }, \ - { "climb_rate", NULL, MAVLINK_TYPE_INT8_T, 0, 32, offsetof(mavlink_high_latency_t, climb_rate) }, \ - { "gps_nsat", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_high_latency_t, gps_nsat) }, \ - { "gps_fix_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_high_latency_t, gps_fix_type) }, \ - { "battery_remaining", NULL, MAVLINK_TYPE_UINT8_T, 0, 35, offsetof(mavlink_high_latency_t, battery_remaining) }, \ - { "temperature", NULL, MAVLINK_TYPE_INT8_T, 0, 36, offsetof(mavlink_high_latency_t, temperature) }, \ - { "temperature_air", NULL, MAVLINK_TYPE_INT8_T, 0, 37, offsetof(mavlink_high_latency_t, temperature_air) }, \ - { "failsafe", NULL, MAVLINK_TYPE_UINT8_T, 0, 38, offsetof(mavlink_high_latency_t, failsafe) }, \ - { "wp_num", NULL, MAVLINK_TYPE_UINT8_T, 0, 39, offsetof(mavlink_high_latency_t, wp_num) }, \ - { "wp_distance", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_high_latency_t, wp_distance) }, \ - } \ -} -#endif - -/** - * @brief Pack a high_latency message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param base_mode Bitmap of enabled system modes. - * @param custom_mode A bitfield for use for autopilot-specific flags. - * @param landed_state The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown. - * @param roll [cdeg] roll - * @param pitch [cdeg] pitch - * @param heading [cdeg] heading - * @param throttle [%] throttle (percentage) - * @param heading_sp [cdeg] heading setpoint - * @param latitude [degE7] Latitude - * @param longitude [degE7] Longitude - * @param altitude_amsl [m] Altitude above mean sea level - * @param altitude_sp [m] Altitude setpoint relative to the home position - * @param airspeed [m/s] airspeed - * @param airspeed_sp [m/s] airspeed setpoint - * @param groundspeed [m/s] groundspeed - * @param climb_rate [m/s] climb rate - * @param gps_nsat Number of satellites visible. If unknown, set to UINT8_MAX - * @param gps_fix_type GPS Fix type. - * @param battery_remaining [%] Remaining battery (percentage) - * @param temperature [degC] Autopilot temperature (degrees C) - * @param temperature_air [degC] Air temperature (degrees C) from airspeed sensor - * @param failsafe failsafe (each bit represents a failsafe where 0=ok, 1=failsafe active (bit0:RC, bit1:batt, bit2:GPS, bit3:GCS, bit4:fence) - * @param wp_num current waypoint number - * @param wp_distance [m] distance to target - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_high_latency_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t base_mode, uint32_t custom_mode, uint8_t landed_state, int16_t roll, int16_t pitch, uint16_t heading, int8_t throttle, int16_t heading_sp, int32_t latitude, int32_t longitude, int16_t altitude_amsl, int16_t altitude_sp, uint8_t airspeed, uint8_t airspeed_sp, uint8_t groundspeed, int8_t climb_rate, uint8_t gps_nsat, uint8_t gps_fix_type, uint8_t battery_remaining, int8_t temperature, int8_t temperature_air, uint8_t failsafe, uint8_t wp_num, uint16_t wp_distance) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_HIGH_LATENCY_LEN]; - _mav_put_uint32_t(buf, 0, custom_mode); - _mav_put_int32_t(buf, 4, latitude); - _mav_put_int32_t(buf, 8, longitude); - _mav_put_int16_t(buf, 12, roll); - _mav_put_int16_t(buf, 14, pitch); - _mav_put_uint16_t(buf, 16, heading); - _mav_put_int16_t(buf, 18, heading_sp); - _mav_put_int16_t(buf, 20, altitude_amsl); - _mav_put_int16_t(buf, 22, altitude_sp); - _mav_put_uint16_t(buf, 24, wp_distance); - _mav_put_uint8_t(buf, 26, base_mode); - _mav_put_uint8_t(buf, 27, landed_state); - _mav_put_int8_t(buf, 28, throttle); - _mav_put_uint8_t(buf, 29, airspeed); - _mav_put_uint8_t(buf, 30, airspeed_sp); - _mav_put_uint8_t(buf, 31, groundspeed); - _mav_put_int8_t(buf, 32, climb_rate); - _mav_put_uint8_t(buf, 33, gps_nsat); - _mav_put_uint8_t(buf, 34, gps_fix_type); - _mav_put_uint8_t(buf, 35, battery_remaining); - _mav_put_int8_t(buf, 36, temperature); - _mav_put_int8_t(buf, 37, temperature_air); - _mav_put_uint8_t(buf, 38, failsafe); - _mav_put_uint8_t(buf, 39, wp_num); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIGH_LATENCY_LEN); -#else - mavlink_high_latency_t packet; - packet.custom_mode = custom_mode; - packet.latitude = latitude; - packet.longitude = longitude; - packet.roll = roll; - packet.pitch = pitch; - packet.heading = heading; - packet.heading_sp = heading_sp; - packet.altitude_amsl = altitude_amsl; - packet.altitude_sp = altitude_sp; - packet.wp_distance = wp_distance; - packet.base_mode = base_mode; - packet.landed_state = landed_state; - packet.throttle = throttle; - packet.airspeed = airspeed; - packet.airspeed_sp = airspeed_sp; - packet.groundspeed = groundspeed; - packet.climb_rate = climb_rate; - packet.gps_nsat = gps_nsat; - packet.gps_fix_type = gps_fix_type; - packet.battery_remaining = battery_remaining; - packet.temperature = temperature; - packet.temperature_air = temperature_air; - packet.failsafe = failsafe; - packet.wp_num = wp_num; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIGH_LATENCY_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_HIGH_LATENCY; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HIGH_LATENCY_MIN_LEN, MAVLINK_MSG_ID_HIGH_LATENCY_LEN, MAVLINK_MSG_ID_HIGH_LATENCY_CRC); -} - -/** - * @brief Pack a high_latency message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param base_mode Bitmap of enabled system modes. - * @param custom_mode A bitfield for use for autopilot-specific flags. - * @param landed_state The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown. - * @param roll [cdeg] roll - * @param pitch [cdeg] pitch - * @param heading [cdeg] heading - * @param throttle [%] throttle (percentage) - * @param heading_sp [cdeg] heading setpoint - * @param latitude [degE7] Latitude - * @param longitude [degE7] Longitude - * @param altitude_amsl [m] Altitude above mean sea level - * @param altitude_sp [m] Altitude setpoint relative to the home position - * @param airspeed [m/s] airspeed - * @param airspeed_sp [m/s] airspeed setpoint - * @param groundspeed [m/s] groundspeed - * @param climb_rate [m/s] climb rate - * @param gps_nsat Number of satellites visible. If unknown, set to UINT8_MAX - * @param gps_fix_type GPS Fix type. - * @param battery_remaining [%] Remaining battery (percentage) - * @param temperature [degC] Autopilot temperature (degrees C) - * @param temperature_air [degC] Air temperature (degrees C) from airspeed sensor - * @param failsafe failsafe (each bit represents a failsafe where 0=ok, 1=failsafe active (bit0:RC, bit1:batt, bit2:GPS, bit3:GCS, bit4:fence) - * @param wp_num current waypoint number - * @param wp_distance [m] distance to target - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_high_latency_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t base_mode,uint32_t custom_mode,uint8_t landed_state,int16_t roll,int16_t pitch,uint16_t heading,int8_t throttle,int16_t heading_sp,int32_t latitude,int32_t longitude,int16_t altitude_amsl,int16_t altitude_sp,uint8_t airspeed,uint8_t airspeed_sp,uint8_t groundspeed,int8_t climb_rate,uint8_t gps_nsat,uint8_t gps_fix_type,uint8_t battery_remaining,int8_t temperature,int8_t temperature_air,uint8_t failsafe,uint8_t wp_num,uint16_t wp_distance) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_HIGH_LATENCY_LEN]; - _mav_put_uint32_t(buf, 0, custom_mode); - _mav_put_int32_t(buf, 4, latitude); - _mav_put_int32_t(buf, 8, longitude); - _mav_put_int16_t(buf, 12, roll); - _mav_put_int16_t(buf, 14, pitch); - _mav_put_uint16_t(buf, 16, heading); - _mav_put_int16_t(buf, 18, heading_sp); - _mav_put_int16_t(buf, 20, altitude_amsl); - _mav_put_int16_t(buf, 22, altitude_sp); - _mav_put_uint16_t(buf, 24, wp_distance); - _mav_put_uint8_t(buf, 26, base_mode); - _mav_put_uint8_t(buf, 27, landed_state); - _mav_put_int8_t(buf, 28, throttle); - _mav_put_uint8_t(buf, 29, airspeed); - _mav_put_uint8_t(buf, 30, airspeed_sp); - _mav_put_uint8_t(buf, 31, groundspeed); - _mav_put_int8_t(buf, 32, climb_rate); - _mav_put_uint8_t(buf, 33, gps_nsat); - _mav_put_uint8_t(buf, 34, gps_fix_type); - _mav_put_uint8_t(buf, 35, battery_remaining); - _mav_put_int8_t(buf, 36, temperature); - _mav_put_int8_t(buf, 37, temperature_air); - _mav_put_uint8_t(buf, 38, failsafe); - _mav_put_uint8_t(buf, 39, wp_num); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIGH_LATENCY_LEN); -#else - mavlink_high_latency_t packet; - packet.custom_mode = custom_mode; - packet.latitude = latitude; - packet.longitude = longitude; - packet.roll = roll; - packet.pitch = pitch; - packet.heading = heading; - packet.heading_sp = heading_sp; - packet.altitude_amsl = altitude_amsl; - packet.altitude_sp = altitude_sp; - packet.wp_distance = wp_distance; - packet.base_mode = base_mode; - packet.landed_state = landed_state; - packet.throttle = throttle; - packet.airspeed = airspeed; - packet.airspeed_sp = airspeed_sp; - packet.groundspeed = groundspeed; - packet.climb_rate = climb_rate; - packet.gps_nsat = gps_nsat; - packet.gps_fix_type = gps_fix_type; - packet.battery_remaining = battery_remaining; - packet.temperature = temperature; - packet.temperature_air = temperature_air; - packet.failsafe = failsafe; - packet.wp_num = wp_num; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIGH_LATENCY_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_HIGH_LATENCY; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HIGH_LATENCY_MIN_LEN, MAVLINK_MSG_ID_HIGH_LATENCY_LEN, MAVLINK_MSG_ID_HIGH_LATENCY_CRC); -} - -/** - * @brief Encode a high_latency struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param high_latency C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_high_latency_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_high_latency_t* high_latency) -{ - return mavlink_msg_high_latency_pack(system_id, component_id, msg, high_latency->base_mode, high_latency->custom_mode, high_latency->landed_state, high_latency->roll, high_latency->pitch, high_latency->heading, high_latency->throttle, high_latency->heading_sp, high_latency->latitude, high_latency->longitude, high_latency->altitude_amsl, high_latency->altitude_sp, high_latency->airspeed, high_latency->airspeed_sp, high_latency->groundspeed, high_latency->climb_rate, high_latency->gps_nsat, high_latency->gps_fix_type, high_latency->battery_remaining, high_latency->temperature, high_latency->temperature_air, high_latency->failsafe, high_latency->wp_num, high_latency->wp_distance); -} - -/** - * @brief Encode a high_latency struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param high_latency C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_high_latency_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_high_latency_t* high_latency) -{ - return mavlink_msg_high_latency_pack_chan(system_id, component_id, chan, msg, high_latency->base_mode, high_latency->custom_mode, high_latency->landed_state, high_latency->roll, high_latency->pitch, high_latency->heading, high_latency->throttle, high_latency->heading_sp, high_latency->latitude, high_latency->longitude, high_latency->altitude_amsl, high_latency->altitude_sp, high_latency->airspeed, high_latency->airspeed_sp, high_latency->groundspeed, high_latency->climb_rate, high_latency->gps_nsat, high_latency->gps_fix_type, high_latency->battery_remaining, high_latency->temperature, high_latency->temperature_air, high_latency->failsafe, high_latency->wp_num, high_latency->wp_distance); -} - -/** - * @brief Send a high_latency message - * @param chan MAVLink channel to send the message - * - * @param base_mode Bitmap of enabled system modes. - * @param custom_mode A bitfield for use for autopilot-specific flags. - * @param landed_state The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown. - * @param roll [cdeg] roll - * @param pitch [cdeg] pitch - * @param heading [cdeg] heading - * @param throttle [%] throttle (percentage) - * @param heading_sp [cdeg] heading setpoint - * @param latitude [degE7] Latitude - * @param longitude [degE7] Longitude - * @param altitude_amsl [m] Altitude above mean sea level - * @param altitude_sp [m] Altitude setpoint relative to the home position - * @param airspeed [m/s] airspeed - * @param airspeed_sp [m/s] airspeed setpoint - * @param groundspeed [m/s] groundspeed - * @param climb_rate [m/s] climb rate - * @param gps_nsat Number of satellites visible. If unknown, set to UINT8_MAX - * @param gps_fix_type GPS Fix type. - * @param battery_remaining [%] Remaining battery (percentage) - * @param temperature [degC] Autopilot temperature (degrees C) - * @param temperature_air [degC] Air temperature (degrees C) from airspeed sensor - * @param failsafe failsafe (each bit represents a failsafe where 0=ok, 1=failsafe active (bit0:RC, bit1:batt, bit2:GPS, bit3:GCS, bit4:fence) - * @param wp_num current waypoint number - * @param wp_distance [m] distance to target - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_high_latency_send(mavlink_channel_t chan, uint8_t base_mode, uint32_t custom_mode, uint8_t landed_state, int16_t roll, int16_t pitch, uint16_t heading, int8_t throttle, int16_t heading_sp, int32_t latitude, int32_t longitude, int16_t altitude_amsl, int16_t altitude_sp, uint8_t airspeed, uint8_t airspeed_sp, uint8_t groundspeed, int8_t climb_rate, uint8_t gps_nsat, uint8_t gps_fix_type, uint8_t battery_remaining, int8_t temperature, int8_t temperature_air, uint8_t failsafe, uint8_t wp_num, uint16_t wp_distance) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_HIGH_LATENCY_LEN]; - _mav_put_uint32_t(buf, 0, custom_mode); - _mav_put_int32_t(buf, 4, latitude); - _mav_put_int32_t(buf, 8, longitude); - _mav_put_int16_t(buf, 12, roll); - _mav_put_int16_t(buf, 14, pitch); - _mav_put_uint16_t(buf, 16, heading); - _mav_put_int16_t(buf, 18, heading_sp); - _mav_put_int16_t(buf, 20, altitude_amsl); - _mav_put_int16_t(buf, 22, altitude_sp); - _mav_put_uint16_t(buf, 24, wp_distance); - _mav_put_uint8_t(buf, 26, base_mode); - _mav_put_uint8_t(buf, 27, landed_state); - _mav_put_int8_t(buf, 28, throttle); - _mav_put_uint8_t(buf, 29, airspeed); - _mav_put_uint8_t(buf, 30, airspeed_sp); - _mav_put_uint8_t(buf, 31, groundspeed); - _mav_put_int8_t(buf, 32, climb_rate); - _mav_put_uint8_t(buf, 33, gps_nsat); - _mav_put_uint8_t(buf, 34, gps_fix_type); - _mav_put_uint8_t(buf, 35, battery_remaining); - _mav_put_int8_t(buf, 36, temperature); - _mav_put_int8_t(buf, 37, temperature_air); - _mav_put_uint8_t(buf, 38, failsafe); - _mav_put_uint8_t(buf, 39, wp_num); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIGH_LATENCY, buf, MAVLINK_MSG_ID_HIGH_LATENCY_MIN_LEN, MAVLINK_MSG_ID_HIGH_LATENCY_LEN, MAVLINK_MSG_ID_HIGH_LATENCY_CRC); -#else - mavlink_high_latency_t packet; - packet.custom_mode = custom_mode; - packet.latitude = latitude; - packet.longitude = longitude; - packet.roll = roll; - packet.pitch = pitch; - packet.heading = heading; - packet.heading_sp = heading_sp; - packet.altitude_amsl = altitude_amsl; - packet.altitude_sp = altitude_sp; - packet.wp_distance = wp_distance; - packet.base_mode = base_mode; - packet.landed_state = landed_state; - packet.throttle = throttle; - packet.airspeed = airspeed; - packet.airspeed_sp = airspeed_sp; - packet.groundspeed = groundspeed; - packet.climb_rate = climb_rate; - packet.gps_nsat = gps_nsat; - packet.gps_fix_type = gps_fix_type; - packet.battery_remaining = battery_remaining; - packet.temperature = temperature; - packet.temperature_air = temperature_air; - packet.failsafe = failsafe; - packet.wp_num = wp_num; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIGH_LATENCY, (const char *)&packet, MAVLINK_MSG_ID_HIGH_LATENCY_MIN_LEN, MAVLINK_MSG_ID_HIGH_LATENCY_LEN, MAVLINK_MSG_ID_HIGH_LATENCY_CRC); -#endif -} - -/** - * @brief Send a high_latency message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_high_latency_send_struct(mavlink_channel_t chan, const mavlink_high_latency_t* high_latency) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_high_latency_send(chan, high_latency->base_mode, high_latency->custom_mode, high_latency->landed_state, high_latency->roll, high_latency->pitch, high_latency->heading, high_latency->throttle, high_latency->heading_sp, high_latency->latitude, high_latency->longitude, high_latency->altitude_amsl, high_latency->altitude_sp, high_latency->airspeed, high_latency->airspeed_sp, high_latency->groundspeed, high_latency->climb_rate, high_latency->gps_nsat, high_latency->gps_fix_type, high_latency->battery_remaining, high_latency->temperature, high_latency->temperature_air, high_latency->failsafe, high_latency->wp_num, high_latency->wp_distance); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIGH_LATENCY, (const char *)high_latency, MAVLINK_MSG_ID_HIGH_LATENCY_MIN_LEN, MAVLINK_MSG_ID_HIGH_LATENCY_LEN, MAVLINK_MSG_ID_HIGH_LATENCY_CRC); -#endif -} - -#if MAVLINK_MSG_ID_HIGH_LATENCY_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_high_latency_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t base_mode, uint32_t custom_mode, uint8_t landed_state, int16_t roll, int16_t pitch, uint16_t heading, int8_t throttle, int16_t heading_sp, int32_t latitude, int32_t longitude, int16_t altitude_amsl, int16_t altitude_sp, uint8_t airspeed, uint8_t airspeed_sp, uint8_t groundspeed, int8_t climb_rate, uint8_t gps_nsat, uint8_t gps_fix_type, uint8_t battery_remaining, int8_t temperature, int8_t temperature_air, uint8_t failsafe, uint8_t wp_num, uint16_t wp_distance) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, custom_mode); - _mav_put_int32_t(buf, 4, latitude); - _mav_put_int32_t(buf, 8, longitude); - _mav_put_int16_t(buf, 12, roll); - _mav_put_int16_t(buf, 14, pitch); - _mav_put_uint16_t(buf, 16, heading); - _mav_put_int16_t(buf, 18, heading_sp); - _mav_put_int16_t(buf, 20, altitude_amsl); - _mav_put_int16_t(buf, 22, altitude_sp); - _mav_put_uint16_t(buf, 24, wp_distance); - _mav_put_uint8_t(buf, 26, base_mode); - _mav_put_uint8_t(buf, 27, landed_state); - _mav_put_int8_t(buf, 28, throttle); - _mav_put_uint8_t(buf, 29, airspeed); - _mav_put_uint8_t(buf, 30, airspeed_sp); - _mav_put_uint8_t(buf, 31, groundspeed); - _mav_put_int8_t(buf, 32, climb_rate); - _mav_put_uint8_t(buf, 33, gps_nsat); - _mav_put_uint8_t(buf, 34, gps_fix_type); - _mav_put_uint8_t(buf, 35, battery_remaining); - _mav_put_int8_t(buf, 36, temperature); - _mav_put_int8_t(buf, 37, temperature_air); - _mav_put_uint8_t(buf, 38, failsafe); - _mav_put_uint8_t(buf, 39, wp_num); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIGH_LATENCY, buf, MAVLINK_MSG_ID_HIGH_LATENCY_MIN_LEN, MAVLINK_MSG_ID_HIGH_LATENCY_LEN, MAVLINK_MSG_ID_HIGH_LATENCY_CRC); -#else - mavlink_high_latency_t *packet = (mavlink_high_latency_t *)msgbuf; - packet->custom_mode = custom_mode; - packet->latitude = latitude; - packet->longitude = longitude; - packet->roll = roll; - packet->pitch = pitch; - packet->heading = heading; - packet->heading_sp = heading_sp; - packet->altitude_amsl = altitude_amsl; - packet->altitude_sp = altitude_sp; - packet->wp_distance = wp_distance; - packet->base_mode = base_mode; - packet->landed_state = landed_state; - packet->throttle = throttle; - packet->airspeed = airspeed; - packet->airspeed_sp = airspeed_sp; - packet->groundspeed = groundspeed; - packet->climb_rate = climb_rate; - packet->gps_nsat = gps_nsat; - packet->gps_fix_type = gps_fix_type; - packet->battery_remaining = battery_remaining; - packet->temperature = temperature; - packet->temperature_air = temperature_air; - packet->failsafe = failsafe; - packet->wp_num = wp_num; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIGH_LATENCY, (const char *)packet, MAVLINK_MSG_ID_HIGH_LATENCY_MIN_LEN, MAVLINK_MSG_ID_HIGH_LATENCY_LEN, MAVLINK_MSG_ID_HIGH_LATENCY_CRC); -#endif -} -#endif - -#endif - -// MESSAGE HIGH_LATENCY UNPACKING - - -/** - * @brief Get field base_mode from high_latency message - * - * @return Bitmap of enabled system modes. - */ -static inline uint8_t mavlink_msg_high_latency_get_base_mode(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 26); -} - -/** - * @brief Get field custom_mode from high_latency message - * - * @return A bitfield for use for autopilot-specific flags. - */ -static inline uint32_t mavlink_msg_high_latency_get_custom_mode(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field landed_state from high_latency message - * - * @return The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown. - */ -static inline uint8_t mavlink_msg_high_latency_get_landed_state(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 27); -} - -/** - * @brief Get field roll from high_latency message - * - * @return [cdeg] roll - */ -static inline int16_t mavlink_msg_high_latency_get_roll(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 12); -} - -/** - * @brief Get field pitch from high_latency message - * - * @return [cdeg] pitch - */ -static inline int16_t mavlink_msg_high_latency_get_pitch(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 14); -} - -/** - * @brief Get field heading from high_latency message - * - * @return [cdeg] heading - */ -static inline uint16_t mavlink_msg_high_latency_get_heading(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 16); -} - -/** - * @brief Get field throttle from high_latency message - * - * @return [%] throttle (percentage) - */ -static inline int8_t mavlink_msg_high_latency_get_throttle(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int8_t(msg, 28); -} - -/** - * @brief Get field heading_sp from high_latency message - * - * @return [cdeg] heading setpoint - */ -static inline int16_t mavlink_msg_high_latency_get_heading_sp(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 18); -} - -/** - * @brief Get field latitude from high_latency message - * - * @return [degE7] Latitude - */ -static inline int32_t mavlink_msg_high_latency_get_latitude(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 4); -} - -/** - * @brief Get field longitude from high_latency message - * - * @return [degE7] Longitude - */ -static inline int32_t mavlink_msg_high_latency_get_longitude(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 8); -} - -/** - * @brief Get field altitude_amsl from high_latency message - * - * @return [m] Altitude above mean sea level - */ -static inline int16_t mavlink_msg_high_latency_get_altitude_amsl(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 20); -} - -/** - * @brief Get field altitude_sp from high_latency message - * - * @return [m] Altitude setpoint relative to the home position - */ -static inline int16_t mavlink_msg_high_latency_get_altitude_sp(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 22); -} - -/** - * @brief Get field airspeed from high_latency message - * - * @return [m/s] airspeed - */ -static inline uint8_t mavlink_msg_high_latency_get_airspeed(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 29); -} - -/** - * @brief Get field airspeed_sp from high_latency message - * - * @return [m/s] airspeed setpoint - */ -static inline uint8_t mavlink_msg_high_latency_get_airspeed_sp(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 30); -} - -/** - * @brief Get field groundspeed from high_latency message - * - * @return [m/s] groundspeed - */ -static inline uint8_t mavlink_msg_high_latency_get_groundspeed(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 31); -} - -/** - * @brief Get field climb_rate from high_latency message - * - * @return [m/s] climb rate - */ -static inline int8_t mavlink_msg_high_latency_get_climb_rate(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int8_t(msg, 32); -} - -/** - * @brief Get field gps_nsat from high_latency message - * - * @return Number of satellites visible. If unknown, set to UINT8_MAX - */ -static inline uint8_t mavlink_msg_high_latency_get_gps_nsat(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 33); -} - -/** - * @brief Get field gps_fix_type from high_latency message - * - * @return GPS Fix type. - */ -static inline uint8_t mavlink_msg_high_latency_get_gps_fix_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 34); -} - -/** - * @brief Get field battery_remaining from high_latency message - * - * @return [%] Remaining battery (percentage) - */ -static inline uint8_t mavlink_msg_high_latency_get_battery_remaining(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 35); -} - -/** - * @brief Get field temperature from high_latency message - * - * @return [degC] Autopilot temperature (degrees C) - */ -static inline int8_t mavlink_msg_high_latency_get_temperature(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int8_t(msg, 36); -} - -/** - * @brief Get field temperature_air from high_latency message - * - * @return [degC] Air temperature (degrees C) from airspeed sensor - */ -static inline int8_t mavlink_msg_high_latency_get_temperature_air(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int8_t(msg, 37); -} - -/** - * @brief Get field failsafe from high_latency message - * - * @return failsafe (each bit represents a failsafe where 0=ok, 1=failsafe active (bit0:RC, bit1:batt, bit2:GPS, bit3:GCS, bit4:fence) - */ -static inline uint8_t mavlink_msg_high_latency_get_failsafe(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 38); -} - -/** - * @brief Get field wp_num from high_latency message - * - * @return current waypoint number - */ -static inline uint8_t mavlink_msg_high_latency_get_wp_num(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 39); -} - -/** - * @brief Get field wp_distance from high_latency message - * - * @return [m] distance to target - */ -static inline uint16_t mavlink_msg_high_latency_get_wp_distance(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 24); -} - -/** - * @brief Decode a high_latency message into a struct - * - * @param msg The message to decode - * @param high_latency C-struct to decode the message contents into - */ -static inline void mavlink_msg_high_latency_decode(const mavlink_message_t* msg, mavlink_high_latency_t* high_latency) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - high_latency->custom_mode = mavlink_msg_high_latency_get_custom_mode(msg); - high_latency->latitude = mavlink_msg_high_latency_get_latitude(msg); - high_latency->longitude = mavlink_msg_high_latency_get_longitude(msg); - high_latency->roll = mavlink_msg_high_latency_get_roll(msg); - high_latency->pitch = mavlink_msg_high_latency_get_pitch(msg); - high_latency->heading = mavlink_msg_high_latency_get_heading(msg); - high_latency->heading_sp = mavlink_msg_high_latency_get_heading_sp(msg); - high_latency->altitude_amsl = mavlink_msg_high_latency_get_altitude_amsl(msg); - high_latency->altitude_sp = mavlink_msg_high_latency_get_altitude_sp(msg); - high_latency->wp_distance = mavlink_msg_high_latency_get_wp_distance(msg); - high_latency->base_mode = mavlink_msg_high_latency_get_base_mode(msg); - high_latency->landed_state = mavlink_msg_high_latency_get_landed_state(msg); - high_latency->throttle = mavlink_msg_high_latency_get_throttle(msg); - high_latency->airspeed = mavlink_msg_high_latency_get_airspeed(msg); - high_latency->airspeed_sp = mavlink_msg_high_latency_get_airspeed_sp(msg); - high_latency->groundspeed = mavlink_msg_high_latency_get_groundspeed(msg); - high_latency->climb_rate = mavlink_msg_high_latency_get_climb_rate(msg); - high_latency->gps_nsat = mavlink_msg_high_latency_get_gps_nsat(msg); - high_latency->gps_fix_type = mavlink_msg_high_latency_get_gps_fix_type(msg); - high_latency->battery_remaining = mavlink_msg_high_latency_get_battery_remaining(msg); - high_latency->temperature = mavlink_msg_high_latency_get_temperature(msg); - high_latency->temperature_air = mavlink_msg_high_latency_get_temperature_air(msg); - high_latency->failsafe = mavlink_msg_high_latency_get_failsafe(msg); - high_latency->wp_num = mavlink_msg_high_latency_get_wp_num(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_HIGH_LATENCY_LEN? msg->len : MAVLINK_MSG_ID_HIGH_LATENCY_LEN; - memset(high_latency, 0, MAVLINK_MSG_ID_HIGH_LATENCY_LEN); - memcpy(high_latency, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_high_latency2.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_high_latency2.h deleted file mode 100644 index 39d24306..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_high_latency2.h +++ /dev/null @@ -1,863 +0,0 @@ -#pragma once -// MESSAGE HIGH_LATENCY2 PACKING - -#define MAVLINK_MSG_ID_HIGH_LATENCY2 235 - - -typedef struct __mavlink_high_latency2_t { - uint32_t timestamp; /*< [ms] Timestamp (milliseconds since boot or Unix epoch)*/ - int32_t latitude; /*< [degE7] Latitude*/ - int32_t longitude; /*< [degE7] Longitude*/ - uint16_t custom_mode; /*< A bitfield for use for autopilot-specific flags (2 byte version).*/ - int16_t altitude; /*< [m] Altitude above mean sea level*/ - int16_t target_altitude; /*< [m] Altitude setpoint*/ - uint16_t target_distance; /*< [dam] Distance to target waypoint or position*/ - uint16_t wp_num; /*< Current waypoint number*/ - uint16_t failure_flags; /*< Bitmap of failure flags.*/ - uint8_t type; /*< Type of the MAV (quadrotor, helicopter, etc.)*/ - uint8_t autopilot; /*< Autopilot type / class. Use MAV_AUTOPILOT_INVALID for components that are not flight controllers.*/ - uint8_t heading; /*< [deg/2] Heading*/ - uint8_t target_heading; /*< [deg/2] Heading setpoint*/ - uint8_t throttle; /*< [%] Throttle*/ - uint8_t airspeed; /*< [m/s*5] Airspeed*/ - uint8_t airspeed_sp; /*< [m/s*5] Airspeed setpoint*/ - uint8_t groundspeed; /*< [m/s*5] Groundspeed*/ - uint8_t windspeed; /*< [m/s*5] Windspeed*/ - uint8_t wind_heading; /*< [deg/2] Wind heading*/ - uint8_t eph; /*< [dm] Maximum error horizontal position since last message*/ - uint8_t epv; /*< [dm] Maximum error vertical position since last message*/ - int8_t temperature_air; /*< [degC] Air temperature from airspeed sensor*/ - int8_t climb_rate; /*< [dm/s] Maximum climb rate magnitude since last message*/ - int8_t battery; /*< [%] Battery level (-1 if field not provided).*/ - int8_t custom0; /*< Field for custom payload.*/ - int8_t custom1; /*< Field for custom payload.*/ - int8_t custom2; /*< Field for custom payload.*/ -} mavlink_high_latency2_t; - -#define MAVLINK_MSG_ID_HIGH_LATENCY2_LEN 42 -#define MAVLINK_MSG_ID_HIGH_LATENCY2_MIN_LEN 42 -#define MAVLINK_MSG_ID_235_LEN 42 -#define MAVLINK_MSG_ID_235_MIN_LEN 42 - -#define MAVLINK_MSG_ID_HIGH_LATENCY2_CRC 179 -#define MAVLINK_MSG_ID_235_CRC 179 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_HIGH_LATENCY2 { \ - 235, \ - "HIGH_LATENCY2", \ - 27, \ - { { "timestamp", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_high_latency2_t, timestamp) }, \ - { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_high_latency2_t, type) }, \ - { "autopilot", NULL, MAVLINK_TYPE_UINT8_T, 0, 25, offsetof(mavlink_high_latency2_t, autopilot) }, \ - { "custom_mode", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_high_latency2_t, custom_mode) }, \ - { "latitude", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_high_latency2_t, latitude) }, \ - { "longitude", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_high_latency2_t, longitude) }, \ - { "altitude", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_high_latency2_t, altitude) }, \ - { "target_altitude", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_high_latency2_t, target_altitude) }, \ - { "heading", NULL, MAVLINK_TYPE_UINT8_T, 0, 26, offsetof(mavlink_high_latency2_t, heading) }, \ - { "target_heading", NULL, MAVLINK_TYPE_UINT8_T, 0, 27, offsetof(mavlink_high_latency2_t, target_heading) }, \ - { "target_distance", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_high_latency2_t, target_distance) }, \ - { "throttle", NULL, MAVLINK_TYPE_UINT8_T, 0, 28, offsetof(mavlink_high_latency2_t, throttle) }, \ - { "airspeed", NULL, MAVLINK_TYPE_UINT8_T, 0, 29, offsetof(mavlink_high_latency2_t, airspeed) }, \ - { "airspeed_sp", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_high_latency2_t, airspeed_sp) }, \ - { "groundspeed", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_high_latency2_t, groundspeed) }, \ - { "windspeed", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_high_latency2_t, windspeed) }, \ - { "wind_heading", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_high_latency2_t, wind_heading) }, \ - { "eph", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_high_latency2_t, eph) }, \ - { "epv", NULL, MAVLINK_TYPE_UINT8_T, 0, 35, offsetof(mavlink_high_latency2_t, epv) }, \ - { "temperature_air", NULL, MAVLINK_TYPE_INT8_T, 0, 36, offsetof(mavlink_high_latency2_t, temperature_air) }, \ - { "climb_rate", NULL, MAVLINK_TYPE_INT8_T, 0, 37, offsetof(mavlink_high_latency2_t, climb_rate) }, \ - { "battery", NULL, MAVLINK_TYPE_INT8_T, 0, 38, offsetof(mavlink_high_latency2_t, battery) }, \ - { "wp_num", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_high_latency2_t, wp_num) }, \ - { "failure_flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_high_latency2_t, failure_flags) }, \ - { "custom0", NULL, MAVLINK_TYPE_INT8_T, 0, 39, offsetof(mavlink_high_latency2_t, custom0) }, \ - { "custom1", NULL, MAVLINK_TYPE_INT8_T, 0, 40, offsetof(mavlink_high_latency2_t, custom1) }, \ - { "custom2", NULL, MAVLINK_TYPE_INT8_T, 0, 41, offsetof(mavlink_high_latency2_t, custom2) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_HIGH_LATENCY2 { \ - "HIGH_LATENCY2", \ - 27, \ - { { "timestamp", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_high_latency2_t, timestamp) }, \ - { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_high_latency2_t, type) }, \ - { "autopilot", NULL, MAVLINK_TYPE_UINT8_T, 0, 25, offsetof(mavlink_high_latency2_t, autopilot) }, \ - { "custom_mode", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_high_latency2_t, custom_mode) }, \ - { "latitude", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_high_latency2_t, latitude) }, \ - { "longitude", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_high_latency2_t, longitude) }, \ - { "altitude", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_high_latency2_t, altitude) }, \ - { "target_altitude", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_high_latency2_t, target_altitude) }, \ - { "heading", NULL, MAVLINK_TYPE_UINT8_T, 0, 26, offsetof(mavlink_high_latency2_t, heading) }, \ - { "target_heading", NULL, MAVLINK_TYPE_UINT8_T, 0, 27, offsetof(mavlink_high_latency2_t, target_heading) }, \ - { "target_distance", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_high_latency2_t, target_distance) }, \ - { "throttle", NULL, MAVLINK_TYPE_UINT8_T, 0, 28, offsetof(mavlink_high_latency2_t, throttle) }, \ - { "airspeed", NULL, MAVLINK_TYPE_UINT8_T, 0, 29, offsetof(mavlink_high_latency2_t, airspeed) }, \ - { "airspeed_sp", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_high_latency2_t, airspeed_sp) }, \ - { "groundspeed", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_high_latency2_t, groundspeed) }, \ - { "windspeed", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_high_latency2_t, windspeed) }, \ - { "wind_heading", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_high_latency2_t, wind_heading) }, \ - { "eph", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_high_latency2_t, eph) }, \ - { "epv", NULL, MAVLINK_TYPE_UINT8_T, 0, 35, offsetof(mavlink_high_latency2_t, epv) }, \ - { "temperature_air", NULL, MAVLINK_TYPE_INT8_T, 0, 36, offsetof(mavlink_high_latency2_t, temperature_air) }, \ - { "climb_rate", NULL, MAVLINK_TYPE_INT8_T, 0, 37, offsetof(mavlink_high_latency2_t, climb_rate) }, \ - { "battery", NULL, MAVLINK_TYPE_INT8_T, 0, 38, offsetof(mavlink_high_latency2_t, battery) }, \ - { "wp_num", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_high_latency2_t, wp_num) }, \ - { "failure_flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_high_latency2_t, failure_flags) }, \ - { "custom0", NULL, MAVLINK_TYPE_INT8_T, 0, 39, offsetof(mavlink_high_latency2_t, custom0) }, \ - { "custom1", NULL, MAVLINK_TYPE_INT8_T, 0, 40, offsetof(mavlink_high_latency2_t, custom1) }, \ - { "custom2", NULL, MAVLINK_TYPE_INT8_T, 0, 41, offsetof(mavlink_high_latency2_t, custom2) }, \ - } \ -} -#endif - -/** - * @brief Pack a high_latency2 message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param timestamp [ms] Timestamp (milliseconds since boot or Unix epoch) - * @param type Type of the MAV (quadrotor, helicopter, etc.) - * @param autopilot Autopilot type / class. Use MAV_AUTOPILOT_INVALID for components that are not flight controllers. - * @param custom_mode A bitfield for use for autopilot-specific flags (2 byte version). - * @param latitude [degE7] Latitude - * @param longitude [degE7] Longitude - * @param altitude [m] Altitude above mean sea level - * @param target_altitude [m] Altitude setpoint - * @param heading [deg/2] Heading - * @param target_heading [deg/2] Heading setpoint - * @param target_distance [dam] Distance to target waypoint or position - * @param throttle [%] Throttle - * @param airspeed [m/s*5] Airspeed - * @param airspeed_sp [m/s*5] Airspeed setpoint - * @param groundspeed [m/s*5] Groundspeed - * @param windspeed [m/s*5] Windspeed - * @param wind_heading [deg/2] Wind heading - * @param eph [dm] Maximum error horizontal position since last message - * @param epv [dm] Maximum error vertical position since last message - * @param temperature_air [degC] Air temperature from airspeed sensor - * @param climb_rate [dm/s] Maximum climb rate magnitude since last message - * @param battery [%] Battery level (-1 if field not provided). - * @param wp_num Current waypoint number - * @param failure_flags Bitmap of failure flags. - * @param custom0 Field for custom payload. - * @param custom1 Field for custom payload. - * @param custom2 Field for custom payload. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_high_latency2_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint32_t timestamp, uint8_t type, uint8_t autopilot, uint16_t custom_mode, int32_t latitude, int32_t longitude, int16_t altitude, int16_t target_altitude, uint8_t heading, uint8_t target_heading, uint16_t target_distance, uint8_t throttle, uint8_t airspeed, uint8_t airspeed_sp, uint8_t groundspeed, uint8_t windspeed, uint8_t wind_heading, uint8_t eph, uint8_t epv, int8_t temperature_air, int8_t climb_rate, int8_t battery, uint16_t wp_num, uint16_t failure_flags, int8_t custom0, int8_t custom1, int8_t custom2) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_HIGH_LATENCY2_LEN]; - _mav_put_uint32_t(buf, 0, timestamp); - _mav_put_int32_t(buf, 4, latitude); - _mav_put_int32_t(buf, 8, longitude); - _mav_put_uint16_t(buf, 12, custom_mode); - _mav_put_int16_t(buf, 14, altitude); - _mav_put_int16_t(buf, 16, target_altitude); - _mav_put_uint16_t(buf, 18, target_distance); - _mav_put_uint16_t(buf, 20, wp_num); - _mav_put_uint16_t(buf, 22, failure_flags); - _mav_put_uint8_t(buf, 24, type); - _mav_put_uint8_t(buf, 25, autopilot); - _mav_put_uint8_t(buf, 26, heading); - _mav_put_uint8_t(buf, 27, target_heading); - _mav_put_uint8_t(buf, 28, throttle); - _mav_put_uint8_t(buf, 29, airspeed); - _mav_put_uint8_t(buf, 30, airspeed_sp); - _mav_put_uint8_t(buf, 31, groundspeed); - _mav_put_uint8_t(buf, 32, windspeed); - _mav_put_uint8_t(buf, 33, wind_heading); - _mav_put_uint8_t(buf, 34, eph); - _mav_put_uint8_t(buf, 35, epv); - _mav_put_int8_t(buf, 36, temperature_air); - _mav_put_int8_t(buf, 37, climb_rate); - _mav_put_int8_t(buf, 38, battery); - _mav_put_int8_t(buf, 39, custom0); - _mav_put_int8_t(buf, 40, custom1); - _mav_put_int8_t(buf, 41, custom2); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIGH_LATENCY2_LEN); -#else - mavlink_high_latency2_t packet; - packet.timestamp = timestamp; - packet.latitude = latitude; - packet.longitude = longitude; - packet.custom_mode = custom_mode; - packet.altitude = altitude; - packet.target_altitude = target_altitude; - packet.target_distance = target_distance; - packet.wp_num = wp_num; - packet.failure_flags = failure_flags; - packet.type = type; - packet.autopilot = autopilot; - packet.heading = heading; - packet.target_heading = target_heading; - packet.throttle = throttle; - packet.airspeed = airspeed; - packet.airspeed_sp = airspeed_sp; - packet.groundspeed = groundspeed; - packet.windspeed = windspeed; - packet.wind_heading = wind_heading; - packet.eph = eph; - packet.epv = epv; - packet.temperature_air = temperature_air; - packet.climb_rate = climb_rate; - packet.battery = battery; - packet.custom0 = custom0; - packet.custom1 = custom1; - packet.custom2 = custom2; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIGH_LATENCY2_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_HIGH_LATENCY2; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HIGH_LATENCY2_MIN_LEN, MAVLINK_MSG_ID_HIGH_LATENCY2_LEN, MAVLINK_MSG_ID_HIGH_LATENCY2_CRC); -} - -/** - * @brief Pack a high_latency2 message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param timestamp [ms] Timestamp (milliseconds since boot or Unix epoch) - * @param type Type of the MAV (quadrotor, helicopter, etc.) - * @param autopilot Autopilot type / class. Use MAV_AUTOPILOT_INVALID for components that are not flight controllers. - * @param custom_mode A bitfield for use for autopilot-specific flags (2 byte version). - * @param latitude [degE7] Latitude - * @param longitude [degE7] Longitude - * @param altitude [m] Altitude above mean sea level - * @param target_altitude [m] Altitude setpoint - * @param heading [deg/2] Heading - * @param target_heading [deg/2] Heading setpoint - * @param target_distance [dam] Distance to target waypoint or position - * @param throttle [%] Throttle - * @param airspeed [m/s*5] Airspeed - * @param airspeed_sp [m/s*5] Airspeed setpoint - * @param groundspeed [m/s*5] Groundspeed - * @param windspeed [m/s*5] Windspeed - * @param wind_heading [deg/2] Wind heading - * @param eph [dm] Maximum error horizontal position since last message - * @param epv [dm] Maximum error vertical position since last message - * @param temperature_air [degC] Air temperature from airspeed sensor - * @param climb_rate [dm/s] Maximum climb rate magnitude since last message - * @param battery [%] Battery level (-1 if field not provided). - * @param wp_num Current waypoint number - * @param failure_flags Bitmap of failure flags. - * @param custom0 Field for custom payload. - * @param custom1 Field for custom payload. - * @param custom2 Field for custom payload. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_high_latency2_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint32_t timestamp,uint8_t type,uint8_t autopilot,uint16_t custom_mode,int32_t latitude,int32_t longitude,int16_t altitude,int16_t target_altitude,uint8_t heading,uint8_t target_heading,uint16_t target_distance,uint8_t throttle,uint8_t airspeed,uint8_t airspeed_sp,uint8_t groundspeed,uint8_t windspeed,uint8_t wind_heading,uint8_t eph,uint8_t epv,int8_t temperature_air,int8_t climb_rate,int8_t battery,uint16_t wp_num,uint16_t failure_flags,int8_t custom0,int8_t custom1,int8_t custom2) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_HIGH_LATENCY2_LEN]; - _mav_put_uint32_t(buf, 0, timestamp); - _mav_put_int32_t(buf, 4, latitude); - _mav_put_int32_t(buf, 8, longitude); - _mav_put_uint16_t(buf, 12, custom_mode); - _mav_put_int16_t(buf, 14, altitude); - _mav_put_int16_t(buf, 16, target_altitude); - _mav_put_uint16_t(buf, 18, target_distance); - _mav_put_uint16_t(buf, 20, wp_num); - _mav_put_uint16_t(buf, 22, failure_flags); - _mav_put_uint8_t(buf, 24, type); - _mav_put_uint8_t(buf, 25, autopilot); - _mav_put_uint8_t(buf, 26, heading); - _mav_put_uint8_t(buf, 27, target_heading); - _mav_put_uint8_t(buf, 28, throttle); - _mav_put_uint8_t(buf, 29, airspeed); - _mav_put_uint8_t(buf, 30, airspeed_sp); - _mav_put_uint8_t(buf, 31, groundspeed); - _mav_put_uint8_t(buf, 32, windspeed); - _mav_put_uint8_t(buf, 33, wind_heading); - _mav_put_uint8_t(buf, 34, eph); - _mav_put_uint8_t(buf, 35, epv); - _mav_put_int8_t(buf, 36, temperature_air); - _mav_put_int8_t(buf, 37, climb_rate); - _mav_put_int8_t(buf, 38, battery); - _mav_put_int8_t(buf, 39, custom0); - _mav_put_int8_t(buf, 40, custom1); - _mav_put_int8_t(buf, 41, custom2); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIGH_LATENCY2_LEN); -#else - mavlink_high_latency2_t packet; - packet.timestamp = timestamp; - packet.latitude = latitude; - packet.longitude = longitude; - packet.custom_mode = custom_mode; - packet.altitude = altitude; - packet.target_altitude = target_altitude; - packet.target_distance = target_distance; - packet.wp_num = wp_num; - packet.failure_flags = failure_flags; - packet.type = type; - packet.autopilot = autopilot; - packet.heading = heading; - packet.target_heading = target_heading; - packet.throttle = throttle; - packet.airspeed = airspeed; - packet.airspeed_sp = airspeed_sp; - packet.groundspeed = groundspeed; - packet.windspeed = windspeed; - packet.wind_heading = wind_heading; - packet.eph = eph; - packet.epv = epv; - packet.temperature_air = temperature_air; - packet.climb_rate = climb_rate; - packet.battery = battery; - packet.custom0 = custom0; - packet.custom1 = custom1; - packet.custom2 = custom2; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIGH_LATENCY2_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_HIGH_LATENCY2; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HIGH_LATENCY2_MIN_LEN, MAVLINK_MSG_ID_HIGH_LATENCY2_LEN, MAVLINK_MSG_ID_HIGH_LATENCY2_CRC); -} - -/** - * @brief Encode a high_latency2 struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param high_latency2 C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_high_latency2_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_high_latency2_t* high_latency2) -{ - return mavlink_msg_high_latency2_pack(system_id, component_id, msg, high_latency2->timestamp, high_latency2->type, high_latency2->autopilot, high_latency2->custom_mode, high_latency2->latitude, high_latency2->longitude, high_latency2->altitude, high_latency2->target_altitude, high_latency2->heading, high_latency2->target_heading, high_latency2->target_distance, high_latency2->throttle, high_latency2->airspeed, high_latency2->airspeed_sp, high_latency2->groundspeed, high_latency2->windspeed, high_latency2->wind_heading, high_latency2->eph, high_latency2->epv, high_latency2->temperature_air, high_latency2->climb_rate, high_latency2->battery, high_latency2->wp_num, high_latency2->failure_flags, high_latency2->custom0, high_latency2->custom1, high_latency2->custom2); -} - -/** - * @brief Encode a high_latency2 struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param high_latency2 C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_high_latency2_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_high_latency2_t* high_latency2) -{ - return mavlink_msg_high_latency2_pack_chan(system_id, component_id, chan, msg, high_latency2->timestamp, high_latency2->type, high_latency2->autopilot, high_latency2->custom_mode, high_latency2->latitude, high_latency2->longitude, high_latency2->altitude, high_latency2->target_altitude, high_latency2->heading, high_latency2->target_heading, high_latency2->target_distance, high_latency2->throttle, high_latency2->airspeed, high_latency2->airspeed_sp, high_latency2->groundspeed, high_latency2->windspeed, high_latency2->wind_heading, high_latency2->eph, high_latency2->epv, high_latency2->temperature_air, high_latency2->climb_rate, high_latency2->battery, high_latency2->wp_num, high_latency2->failure_flags, high_latency2->custom0, high_latency2->custom1, high_latency2->custom2); -} - -/** - * @brief Send a high_latency2 message - * @param chan MAVLink channel to send the message - * - * @param timestamp [ms] Timestamp (milliseconds since boot or Unix epoch) - * @param type Type of the MAV (quadrotor, helicopter, etc.) - * @param autopilot Autopilot type / class. Use MAV_AUTOPILOT_INVALID for components that are not flight controllers. - * @param custom_mode A bitfield for use for autopilot-specific flags (2 byte version). - * @param latitude [degE7] Latitude - * @param longitude [degE7] Longitude - * @param altitude [m] Altitude above mean sea level - * @param target_altitude [m] Altitude setpoint - * @param heading [deg/2] Heading - * @param target_heading [deg/2] Heading setpoint - * @param target_distance [dam] Distance to target waypoint or position - * @param throttle [%] Throttle - * @param airspeed [m/s*5] Airspeed - * @param airspeed_sp [m/s*5] Airspeed setpoint - * @param groundspeed [m/s*5] Groundspeed - * @param windspeed [m/s*5] Windspeed - * @param wind_heading [deg/2] Wind heading - * @param eph [dm] Maximum error horizontal position since last message - * @param epv [dm] Maximum error vertical position since last message - * @param temperature_air [degC] Air temperature from airspeed sensor - * @param climb_rate [dm/s] Maximum climb rate magnitude since last message - * @param battery [%] Battery level (-1 if field not provided). - * @param wp_num Current waypoint number - * @param failure_flags Bitmap of failure flags. - * @param custom0 Field for custom payload. - * @param custom1 Field for custom payload. - * @param custom2 Field for custom payload. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_high_latency2_send(mavlink_channel_t chan, uint32_t timestamp, uint8_t type, uint8_t autopilot, uint16_t custom_mode, int32_t latitude, int32_t longitude, int16_t altitude, int16_t target_altitude, uint8_t heading, uint8_t target_heading, uint16_t target_distance, uint8_t throttle, uint8_t airspeed, uint8_t airspeed_sp, uint8_t groundspeed, uint8_t windspeed, uint8_t wind_heading, uint8_t eph, uint8_t epv, int8_t temperature_air, int8_t climb_rate, int8_t battery, uint16_t wp_num, uint16_t failure_flags, int8_t custom0, int8_t custom1, int8_t custom2) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_HIGH_LATENCY2_LEN]; - _mav_put_uint32_t(buf, 0, timestamp); - _mav_put_int32_t(buf, 4, latitude); - _mav_put_int32_t(buf, 8, longitude); - _mav_put_uint16_t(buf, 12, custom_mode); - _mav_put_int16_t(buf, 14, altitude); - _mav_put_int16_t(buf, 16, target_altitude); - _mav_put_uint16_t(buf, 18, target_distance); - _mav_put_uint16_t(buf, 20, wp_num); - _mav_put_uint16_t(buf, 22, failure_flags); - _mav_put_uint8_t(buf, 24, type); - _mav_put_uint8_t(buf, 25, autopilot); - _mav_put_uint8_t(buf, 26, heading); - _mav_put_uint8_t(buf, 27, target_heading); - _mav_put_uint8_t(buf, 28, throttle); - _mav_put_uint8_t(buf, 29, airspeed); - _mav_put_uint8_t(buf, 30, airspeed_sp); - _mav_put_uint8_t(buf, 31, groundspeed); - _mav_put_uint8_t(buf, 32, windspeed); - _mav_put_uint8_t(buf, 33, wind_heading); - _mav_put_uint8_t(buf, 34, eph); - _mav_put_uint8_t(buf, 35, epv); - _mav_put_int8_t(buf, 36, temperature_air); - _mav_put_int8_t(buf, 37, climb_rate); - _mav_put_int8_t(buf, 38, battery); - _mav_put_int8_t(buf, 39, custom0); - _mav_put_int8_t(buf, 40, custom1); - _mav_put_int8_t(buf, 41, custom2); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIGH_LATENCY2, buf, MAVLINK_MSG_ID_HIGH_LATENCY2_MIN_LEN, MAVLINK_MSG_ID_HIGH_LATENCY2_LEN, MAVLINK_MSG_ID_HIGH_LATENCY2_CRC); -#else - mavlink_high_latency2_t packet; - packet.timestamp = timestamp; - packet.latitude = latitude; - packet.longitude = longitude; - packet.custom_mode = custom_mode; - packet.altitude = altitude; - packet.target_altitude = target_altitude; - packet.target_distance = target_distance; - packet.wp_num = wp_num; - packet.failure_flags = failure_flags; - packet.type = type; - packet.autopilot = autopilot; - packet.heading = heading; - packet.target_heading = target_heading; - packet.throttle = throttle; - packet.airspeed = airspeed; - packet.airspeed_sp = airspeed_sp; - packet.groundspeed = groundspeed; - packet.windspeed = windspeed; - packet.wind_heading = wind_heading; - packet.eph = eph; - packet.epv = epv; - packet.temperature_air = temperature_air; - packet.climb_rate = climb_rate; - packet.battery = battery; - packet.custom0 = custom0; - packet.custom1 = custom1; - packet.custom2 = custom2; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIGH_LATENCY2, (const char *)&packet, MAVLINK_MSG_ID_HIGH_LATENCY2_MIN_LEN, MAVLINK_MSG_ID_HIGH_LATENCY2_LEN, MAVLINK_MSG_ID_HIGH_LATENCY2_CRC); -#endif -} - -/** - * @brief Send a high_latency2 message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_high_latency2_send_struct(mavlink_channel_t chan, const mavlink_high_latency2_t* high_latency2) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_high_latency2_send(chan, high_latency2->timestamp, high_latency2->type, high_latency2->autopilot, high_latency2->custom_mode, high_latency2->latitude, high_latency2->longitude, high_latency2->altitude, high_latency2->target_altitude, high_latency2->heading, high_latency2->target_heading, high_latency2->target_distance, high_latency2->throttle, high_latency2->airspeed, high_latency2->airspeed_sp, high_latency2->groundspeed, high_latency2->windspeed, high_latency2->wind_heading, high_latency2->eph, high_latency2->epv, high_latency2->temperature_air, high_latency2->climb_rate, high_latency2->battery, high_latency2->wp_num, high_latency2->failure_flags, high_latency2->custom0, high_latency2->custom1, high_latency2->custom2); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIGH_LATENCY2, (const char *)high_latency2, MAVLINK_MSG_ID_HIGH_LATENCY2_MIN_LEN, MAVLINK_MSG_ID_HIGH_LATENCY2_LEN, MAVLINK_MSG_ID_HIGH_LATENCY2_CRC); -#endif -} - -#if MAVLINK_MSG_ID_HIGH_LATENCY2_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_high_latency2_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t timestamp, uint8_t type, uint8_t autopilot, uint16_t custom_mode, int32_t latitude, int32_t longitude, int16_t altitude, int16_t target_altitude, uint8_t heading, uint8_t target_heading, uint16_t target_distance, uint8_t throttle, uint8_t airspeed, uint8_t airspeed_sp, uint8_t groundspeed, uint8_t windspeed, uint8_t wind_heading, uint8_t eph, uint8_t epv, int8_t temperature_air, int8_t climb_rate, int8_t battery, uint16_t wp_num, uint16_t failure_flags, int8_t custom0, int8_t custom1, int8_t custom2) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, timestamp); - _mav_put_int32_t(buf, 4, latitude); - _mav_put_int32_t(buf, 8, longitude); - _mav_put_uint16_t(buf, 12, custom_mode); - _mav_put_int16_t(buf, 14, altitude); - _mav_put_int16_t(buf, 16, target_altitude); - _mav_put_uint16_t(buf, 18, target_distance); - _mav_put_uint16_t(buf, 20, wp_num); - _mav_put_uint16_t(buf, 22, failure_flags); - _mav_put_uint8_t(buf, 24, type); - _mav_put_uint8_t(buf, 25, autopilot); - _mav_put_uint8_t(buf, 26, heading); - _mav_put_uint8_t(buf, 27, target_heading); - _mav_put_uint8_t(buf, 28, throttle); - _mav_put_uint8_t(buf, 29, airspeed); - _mav_put_uint8_t(buf, 30, airspeed_sp); - _mav_put_uint8_t(buf, 31, groundspeed); - _mav_put_uint8_t(buf, 32, windspeed); - _mav_put_uint8_t(buf, 33, wind_heading); - _mav_put_uint8_t(buf, 34, eph); - _mav_put_uint8_t(buf, 35, epv); - _mav_put_int8_t(buf, 36, temperature_air); - _mav_put_int8_t(buf, 37, climb_rate); - _mav_put_int8_t(buf, 38, battery); - _mav_put_int8_t(buf, 39, custom0); - _mav_put_int8_t(buf, 40, custom1); - _mav_put_int8_t(buf, 41, custom2); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIGH_LATENCY2, buf, MAVLINK_MSG_ID_HIGH_LATENCY2_MIN_LEN, MAVLINK_MSG_ID_HIGH_LATENCY2_LEN, MAVLINK_MSG_ID_HIGH_LATENCY2_CRC); -#else - mavlink_high_latency2_t *packet = (mavlink_high_latency2_t *)msgbuf; - packet->timestamp = timestamp; - packet->latitude = latitude; - packet->longitude = longitude; - packet->custom_mode = custom_mode; - packet->altitude = altitude; - packet->target_altitude = target_altitude; - packet->target_distance = target_distance; - packet->wp_num = wp_num; - packet->failure_flags = failure_flags; - packet->type = type; - packet->autopilot = autopilot; - packet->heading = heading; - packet->target_heading = target_heading; - packet->throttle = throttle; - packet->airspeed = airspeed; - packet->airspeed_sp = airspeed_sp; - packet->groundspeed = groundspeed; - packet->windspeed = windspeed; - packet->wind_heading = wind_heading; - packet->eph = eph; - packet->epv = epv; - packet->temperature_air = temperature_air; - packet->climb_rate = climb_rate; - packet->battery = battery; - packet->custom0 = custom0; - packet->custom1 = custom1; - packet->custom2 = custom2; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIGH_LATENCY2, (const char *)packet, MAVLINK_MSG_ID_HIGH_LATENCY2_MIN_LEN, MAVLINK_MSG_ID_HIGH_LATENCY2_LEN, MAVLINK_MSG_ID_HIGH_LATENCY2_CRC); -#endif -} -#endif - -#endif - -// MESSAGE HIGH_LATENCY2 UNPACKING - - -/** - * @brief Get field timestamp from high_latency2 message - * - * @return [ms] Timestamp (milliseconds since boot or Unix epoch) - */ -static inline uint32_t mavlink_msg_high_latency2_get_timestamp(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field type from high_latency2 message - * - * @return Type of the MAV (quadrotor, helicopter, etc.) - */ -static inline uint8_t mavlink_msg_high_latency2_get_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 24); -} - -/** - * @brief Get field autopilot from high_latency2 message - * - * @return Autopilot type / class. Use MAV_AUTOPILOT_INVALID for components that are not flight controllers. - */ -static inline uint8_t mavlink_msg_high_latency2_get_autopilot(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 25); -} - -/** - * @brief Get field custom_mode from high_latency2 message - * - * @return A bitfield for use for autopilot-specific flags (2 byte version). - */ -static inline uint16_t mavlink_msg_high_latency2_get_custom_mode(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 12); -} - -/** - * @brief Get field latitude from high_latency2 message - * - * @return [degE7] Latitude - */ -static inline int32_t mavlink_msg_high_latency2_get_latitude(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 4); -} - -/** - * @brief Get field longitude from high_latency2 message - * - * @return [degE7] Longitude - */ -static inline int32_t mavlink_msg_high_latency2_get_longitude(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 8); -} - -/** - * @brief Get field altitude from high_latency2 message - * - * @return [m] Altitude above mean sea level - */ -static inline int16_t mavlink_msg_high_latency2_get_altitude(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 14); -} - -/** - * @brief Get field target_altitude from high_latency2 message - * - * @return [m] Altitude setpoint - */ -static inline int16_t mavlink_msg_high_latency2_get_target_altitude(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 16); -} - -/** - * @brief Get field heading from high_latency2 message - * - * @return [deg/2] Heading - */ -static inline uint8_t mavlink_msg_high_latency2_get_heading(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 26); -} - -/** - * @brief Get field target_heading from high_latency2 message - * - * @return [deg/2] Heading setpoint - */ -static inline uint8_t mavlink_msg_high_latency2_get_target_heading(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 27); -} - -/** - * @brief Get field target_distance from high_latency2 message - * - * @return [dam] Distance to target waypoint or position - */ -static inline uint16_t mavlink_msg_high_latency2_get_target_distance(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 18); -} - -/** - * @brief Get field throttle from high_latency2 message - * - * @return [%] Throttle - */ -static inline uint8_t mavlink_msg_high_latency2_get_throttle(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 28); -} - -/** - * @brief Get field airspeed from high_latency2 message - * - * @return [m/s*5] Airspeed - */ -static inline uint8_t mavlink_msg_high_latency2_get_airspeed(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 29); -} - -/** - * @brief Get field airspeed_sp from high_latency2 message - * - * @return [m/s*5] Airspeed setpoint - */ -static inline uint8_t mavlink_msg_high_latency2_get_airspeed_sp(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 30); -} - -/** - * @brief Get field groundspeed from high_latency2 message - * - * @return [m/s*5] Groundspeed - */ -static inline uint8_t mavlink_msg_high_latency2_get_groundspeed(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 31); -} - -/** - * @brief Get field windspeed from high_latency2 message - * - * @return [m/s*5] Windspeed - */ -static inline uint8_t mavlink_msg_high_latency2_get_windspeed(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 32); -} - -/** - * @brief Get field wind_heading from high_latency2 message - * - * @return [deg/2] Wind heading - */ -static inline uint8_t mavlink_msg_high_latency2_get_wind_heading(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 33); -} - -/** - * @brief Get field eph from high_latency2 message - * - * @return [dm] Maximum error horizontal position since last message - */ -static inline uint8_t mavlink_msg_high_latency2_get_eph(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 34); -} - -/** - * @brief Get field epv from high_latency2 message - * - * @return [dm] Maximum error vertical position since last message - */ -static inline uint8_t mavlink_msg_high_latency2_get_epv(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 35); -} - -/** - * @brief Get field temperature_air from high_latency2 message - * - * @return [degC] Air temperature from airspeed sensor - */ -static inline int8_t mavlink_msg_high_latency2_get_temperature_air(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int8_t(msg, 36); -} - -/** - * @brief Get field climb_rate from high_latency2 message - * - * @return [dm/s] Maximum climb rate magnitude since last message - */ -static inline int8_t mavlink_msg_high_latency2_get_climb_rate(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int8_t(msg, 37); -} - -/** - * @brief Get field battery from high_latency2 message - * - * @return [%] Battery level (-1 if field not provided). - */ -static inline int8_t mavlink_msg_high_latency2_get_battery(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int8_t(msg, 38); -} - -/** - * @brief Get field wp_num from high_latency2 message - * - * @return Current waypoint number - */ -static inline uint16_t mavlink_msg_high_latency2_get_wp_num(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 20); -} - -/** - * @brief Get field failure_flags from high_latency2 message - * - * @return Bitmap of failure flags. - */ -static inline uint16_t mavlink_msg_high_latency2_get_failure_flags(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 22); -} - -/** - * @brief Get field custom0 from high_latency2 message - * - * @return Field for custom payload. - */ -static inline int8_t mavlink_msg_high_latency2_get_custom0(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int8_t(msg, 39); -} - -/** - * @brief Get field custom1 from high_latency2 message - * - * @return Field for custom payload. - */ -static inline int8_t mavlink_msg_high_latency2_get_custom1(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int8_t(msg, 40); -} - -/** - * @brief Get field custom2 from high_latency2 message - * - * @return Field for custom payload. - */ -static inline int8_t mavlink_msg_high_latency2_get_custom2(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int8_t(msg, 41); -} - -/** - * @brief Decode a high_latency2 message into a struct - * - * @param msg The message to decode - * @param high_latency2 C-struct to decode the message contents into - */ -static inline void mavlink_msg_high_latency2_decode(const mavlink_message_t* msg, mavlink_high_latency2_t* high_latency2) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - high_latency2->timestamp = mavlink_msg_high_latency2_get_timestamp(msg); - high_latency2->latitude = mavlink_msg_high_latency2_get_latitude(msg); - high_latency2->longitude = mavlink_msg_high_latency2_get_longitude(msg); - high_latency2->custom_mode = mavlink_msg_high_latency2_get_custom_mode(msg); - high_latency2->altitude = mavlink_msg_high_latency2_get_altitude(msg); - high_latency2->target_altitude = mavlink_msg_high_latency2_get_target_altitude(msg); - high_latency2->target_distance = mavlink_msg_high_latency2_get_target_distance(msg); - high_latency2->wp_num = mavlink_msg_high_latency2_get_wp_num(msg); - high_latency2->failure_flags = mavlink_msg_high_latency2_get_failure_flags(msg); - high_latency2->type = mavlink_msg_high_latency2_get_type(msg); - high_latency2->autopilot = mavlink_msg_high_latency2_get_autopilot(msg); - high_latency2->heading = mavlink_msg_high_latency2_get_heading(msg); - high_latency2->target_heading = mavlink_msg_high_latency2_get_target_heading(msg); - high_latency2->throttle = mavlink_msg_high_latency2_get_throttle(msg); - high_latency2->airspeed = mavlink_msg_high_latency2_get_airspeed(msg); - high_latency2->airspeed_sp = mavlink_msg_high_latency2_get_airspeed_sp(msg); - high_latency2->groundspeed = mavlink_msg_high_latency2_get_groundspeed(msg); - high_latency2->windspeed = mavlink_msg_high_latency2_get_windspeed(msg); - high_latency2->wind_heading = mavlink_msg_high_latency2_get_wind_heading(msg); - high_latency2->eph = mavlink_msg_high_latency2_get_eph(msg); - high_latency2->epv = mavlink_msg_high_latency2_get_epv(msg); - high_latency2->temperature_air = mavlink_msg_high_latency2_get_temperature_air(msg); - high_latency2->climb_rate = mavlink_msg_high_latency2_get_climb_rate(msg); - high_latency2->battery = mavlink_msg_high_latency2_get_battery(msg); - high_latency2->custom0 = mavlink_msg_high_latency2_get_custom0(msg); - high_latency2->custom1 = mavlink_msg_high_latency2_get_custom1(msg); - high_latency2->custom2 = mavlink_msg_high_latency2_get_custom2(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_HIGH_LATENCY2_LEN? msg->len : MAVLINK_MSG_ID_HIGH_LATENCY2_LEN; - memset(high_latency2, 0, MAVLINK_MSG_ID_HIGH_LATENCY2_LEN); - memcpy(high_latency2, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_highres_imu.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_highres_imu.h deleted file mode 100644 index 0e34c9be..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_highres_imu.h +++ /dev/null @@ -1,588 +0,0 @@ -#pragma once -// MESSAGE HIGHRES_IMU PACKING - -#define MAVLINK_MSG_ID_HIGHRES_IMU 105 - - -typedef struct __mavlink_highres_imu_t { - uint64_t time_usec; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/ - float xacc; /*< [m/s/s] X acceleration*/ - float yacc; /*< [m/s/s] Y acceleration*/ - float zacc; /*< [m/s/s] Z acceleration*/ - float xgyro; /*< [rad/s] Angular speed around X axis*/ - float ygyro; /*< [rad/s] Angular speed around Y axis*/ - float zgyro; /*< [rad/s] Angular speed around Z axis*/ - float xmag; /*< [gauss] X Magnetic field*/ - float ymag; /*< [gauss] Y Magnetic field*/ - float zmag; /*< [gauss] Z Magnetic field*/ - float abs_pressure; /*< [hPa] Absolute pressure*/ - float diff_pressure; /*< [hPa] Differential pressure*/ - float pressure_alt; /*< Altitude calculated from pressure*/ - float temperature; /*< [degC] Temperature*/ - uint16_t fields_updated; /*< Bitmap for fields that have updated since last message*/ - uint8_t id; /*< Id. Ids are numbered from 0 and map to IMUs numbered from 1 (e.g. IMU1 will have a message with id=0)*/ -} mavlink_highres_imu_t; - -#define MAVLINK_MSG_ID_HIGHRES_IMU_LEN 63 -#define MAVLINK_MSG_ID_HIGHRES_IMU_MIN_LEN 62 -#define MAVLINK_MSG_ID_105_LEN 63 -#define MAVLINK_MSG_ID_105_MIN_LEN 62 - -#define MAVLINK_MSG_ID_HIGHRES_IMU_CRC 93 -#define MAVLINK_MSG_ID_105_CRC 93 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_HIGHRES_IMU { \ - 105, \ - "HIGHRES_IMU", \ - 16, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_highres_imu_t, time_usec) }, \ - { "xacc", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_highres_imu_t, xacc) }, \ - { "yacc", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_highres_imu_t, yacc) }, \ - { "zacc", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_highres_imu_t, zacc) }, \ - { "xgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_highres_imu_t, xgyro) }, \ - { "ygyro", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_highres_imu_t, ygyro) }, \ - { "zgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_highres_imu_t, zgyro) }, \ - { "xmag", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_highres_imu_t, xmag) }, \ - { "ymag", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_highres_imu_t, ymag) }, \ - { "zmag", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_highres_imu_t, zmag) }, \ - { "abs_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_highres_imu_t, abs_pressure) }, \ - { "diff_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_highres_imu_t, diff_pressure) }, \ - { "pressure_alt", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_highres_imu_t, pressure_alt) }, \ - { "temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_highres_imu_t, temperature) }, \ - { "fields_updated", NULL, MAVLINK_TYPE_UINT16_T, 0, 60, offsetof(mavlink_highres_imu_t, fields_updated) }, \ - { "id", NULL, MAVLINK_TYPE_UINT8_T, 0, 62, offsetof(mavlink_highres_imu_t, id) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_HIGHRES_IMU { \ - "HIGHRES_IMU", \ - 16, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_highres_imu_t, time_usec) }, \ - { "xacc", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_highres_imu_t, xacc) }, \ - { "yacc", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_highres_imu_t, yacc) }, \ - { "zacc", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_highres_imu_t, zacc) }, \ - { "xgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_highres_imu_t, xgyro) }, \ - { "ygyro", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_highres_imu_t, ygyro) }, \ - { "zgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_highres_imu_t, zgyro) }, \ - { "xmag", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_highres_imu_t, xmag) }, \ - { "ymag", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_highres_imu_t, ymag) }, \ - { "zmag", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_highres_imu_t, zmag) }, \ - { "abs_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_highres_imu_t, abs_pressure) }, \ - { "diff_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_highres_imu_t, diff_pressure) }, \ - { "pressure_alt", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_highres_imu_t, pressure_alt) }, \ - { "temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_highres_imu_t, temperature) }, \ - { "fields_updated", NULL, MAVLINK_TYPE_UINT16_T, 0, 60, offsetof(mavlink_highres_imu_t, fields_updated) }, \ - { "id", NULL, MAVLINK_TYPE_UINT8_T, 0, 62, offsetof(mavlink_highres_imu_t, id) }, \ - } \ -} -#endif - -/** - * @brief Pack a highres_imu message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @param xacc [m/s/s] X acceleration - * @param yacc [m/s/s] Y acceleration - * @param zacc [m/s/s] Z acceleration - * @param xgyro [rad/s] Angular speed around X axis - * @param ygyro [rad/s] Angular speed around Y axis - * @param zgyro [rad/s] Angular speed around Z axis - * @param xmag [gauss] X Magnetic field - * @param ymag [gauss] Y Magnetic field - * @param zmag [gauss] Z Magnetic field - * @param abs_pressure [hPa] Absolute pressure - * @param diff_pressure [hPa] Differential pressure - * @param pressure_alt Altitude calculated from pressure - * @param temperature [degC] Temperature - * @param fields_updated Bitmap for fields that have updated since last message - * @param id Id. Ids are numbered from 0 and map to IMUs numbered from 1 (e.g. IMU1 will have a message with id=0) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_highres_imu_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint64_t time_usec, float xacc, float yacc, float zacc, float xgyro, float ygyro, float zgyro, float xmag, float ymag, float zmag, float abs_pressure, float diff_pressure, float pressure_alt, float temperature, uint16_t fields_updated, uint8_t id) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_HIGHRES_IMU_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, xacc); - _mav_put_float(buf, 12, yacc); - _mav_put_float(buf, 16, zacc); - _mav_put_float(buf, 20, xgyro); - _mav_put_float(buf, 24, ygyro); - _mav_put_float(buf, 28, zgyro); - _mav_put_float(buf, 32, xmag); - _mav_put_float(buf, 36, ymag); - _mav_put_float(buf, 40, zmag); - _mav_put_float(buf, 44, abs_pressure); - _mav_put_float(buf, 48, diff_pressure); - _mav_put_float(buf, 52, pressure_alt); - _mav_put_float(buf, 56, temperature); - _mav_put_uint16_t(buf, 60, fields_updated); - _mav_put_uint8_t(buf, 62, id); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIGHRES_IMU_LEN); -#else - mavlink_highres_imu_t packet; - packet.time_usec = time_usec; - packet.xacc = xacc; - packet.yacc = yacc; - packet.zacc = zacc; - packet.xgyro = xgyro; - packet.ygyro = ygyro; - packet.zgyro = zgyro; - packet.xmag = xmag; - packet.ymag = ymag; - packet.zmag = zmag; - packet.abs_pressure = abs_pressure; - packet.diff_pressure = diff_pressure; - packet.pressure_alt = pressure_alt; - packet.temperature = temperature; - packet.fields_updated = fields_updated; - packet.id = id; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIGHRES_IMU_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_HIGHRES_IMU; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HIGHRES_IMU_MIN_LEN, MAVLINK_MSG_ID_HIGHRES_IMU_LEN, MAVLINK_MSG_ID_HIGHRES_IMU_CRC); -} - -/** - * @brief Pack a highres_imu message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @param xacc [m/s/s] X acceleration - * @param yacc [m/s/s] Y acceleration - * @param zacc [m/s/s] Z acceleration - * @param xgyro [rad/s] Angular speed around X axis - * @param ygyro [rad/s] Angular speed around Y axis - * @param zgyro [rad/s] Angular speed around Z axis - * @param xmag [gauss] X Magnetic field - * @param ymag [gauss] Y Magnetic field - * @param zmag [gauss] Z Magnetic field - * @param abs_pressure [hPa] Absolute pressure - * @param diff_pressure [hPa] Differential pressure - * @param pressure_alt Altitude calculated from pressure - * @param temperature [degC] Temperature - * @param fields_updated Bitmap for fields that have updated since last message - * @param id Id. Ids are numbered from 0 and map to IMUs numbered from 1 (e.g. IMU1 will have a message with id=0) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_highres_imu_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint64_t time_usec,float xacc,float yacc,float zacc,float xgyro,float ygyro,float zgyro,float xmag,float ymag,float zmag,float abs_pressure,float diff_pressure,float pressure_alt,float temperature,uint16_t fields_updated,uint8_t id) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_HIGHRES_IMU_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, xacc); - _mav_put_float(buf, 12, yacc); - _mav_put_float(buf, 16, zacc); - _mav_put_float(buf, 20, xgyro); - _mav_put_float(buf, 24, ygyro); - _mav_put_float(buf, 28, zgyro); - _mav_put_float(buf, 32, xmag); - _mav_put_float(buf, 36, ymag); - _mav_put_float(buf, 40, zmag); - _mav_put_float(buf, 44, abs_pressure); - _mav_put_float(buf, 48, diff_pressure); - _mav_put_float(buf, 52, pressure_alt); - _mav_put_float(buf, 56, temperature); - _mav_put_uint16_t(buf, 60, fields_updated); - _mav_put_uint8_t(buf, 62, id); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIGHRES_IMU_LEN); -#else - mavlink_highres_imu_t packet; - packet.time_usec = time_usec; - packet.xacc = xacc; - packet.yacc = yacc; - packet.zacc = zacc; - packet.xgyro = xgyro; - packet.ygyro = ygyro; - packet.zgyro = zgyro; - packet.xmag = xmag; - packet.ymag = ymag; - packet.zmag = zmag; - packet.abs_pressure = abs_pressure; - packet.diff_pressure = diff_pressure; - packet.pressure_alt = pressure_alt; - packet.temperature = temperature; - packet.fields_updated = fields_updated; - packet.id = id; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIGHRES_IMU_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_HIGHRES_IMU; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HIGHRES_IMU_MIN_LEN, MAVLINK_MSG_ID_HIGHRES_IMU_LEN, MAVLINK_MSG_ID_HIGHRES_IMU_CRC); -} - -/** - * @brief Encode a highres_imu struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param highres_imu C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_highres_imu_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_highres_imu_t* highres_imu) -{ - return mavlink_msg_highres_imu_pack(system_id, component_id, msg, highres_imu->time_usec, highres_imu->xacc, highres_imu->yacc, highres_imu->zacc, highres_imu->xgyro, highres_imu->ygyro, highres_imu->zgyro, highres_imu->xmag, highres_imu->ymag, highres_imu->zmag, highres_imu->abs_pressure, highres_imu->diff_pressure, highres_imu->pressure_alt, highres_imu->temperature, highres_imu->fields_updated, highres_imu->id); -} - -/** - * @brief Encode a highres_imu struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param highres_imu C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_highres_imu_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_highres_imu_t* highres_imu) -{ - return mavlink_msg_highres_imu_pack_chan(system_id, component_id, chan, msg, highres_imu->time_usec, highres_imu->xacc, highres_imu->yacc, highres_imu->zacc, highres_imu->xgyro, highres_imu->ygyro, highres_imu->zgyro, highres_imu->xmag, highres_imu->ymag, highres_imu->zmag, highres_imu->abs_pressure, highres_imu->diff_pressure, highres_imu->pressure_alt, highres_imu->temperature, highres_imu->fields_updated, highres_imu->id); -} - -/** - * @brief Send a highres_imu message - * @param chan MAVLink channel to send the message - * - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @param xacc [m/s/s] X acceleration - * @param yacc [m/s/s] Y acceleration - * @param zacc [m/s/s] Z acceleration - * @param xgyro [rad/s] Angular speed around X axis - * @param ygyro [rad/s] Angular speed around Y axis - * @param zgyro [rad/s] Angular speed around Z axis - * @param xmag [gauss] X Magnetic field - * @param ymag [gauss] Y Magnetic field - * @param zmag [gauss] Z Magnetic field - * @param abs_pressure [hPa] Absolute pressure - * @param diff_pressure [hPa] Differential pressure - * @param pressure_alt Altitude calculated from pressure - * @param temperature [degC] Temperature - * @param fields_updated Bitmap for fields that have updated since last message - * @param id Id. Ids are numbered from 0 and map to IMUs numbered from 1 (e.g. IMU1 will have a message with id=0) - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_highres_imu_send(mavlink_channel_t chan, uint64_t time_usec, float xacc, float yacc, float zacc, float xgyro, float ygyro, float zgyro, float xmag, float ymag, float zmag, float abs_pressure, float diff_pressure, float pressure_alt, float temperature, uint16_t fields_updated, uint8_t id) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_HIGHRES_IMU_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, xacc); - _mav_put_float(buf, 12, yacc); - _mav_put_float(buf, 16, zacc); - _mav_put_float(buf, 20, xgyro); - _mav_put_float(buf, 24, ygyro); - _mav_put_float(buf, 28, zgyro); - _mav_put_float(buf, 32, xmag); - _mav_put_float(buf, 36, ymag); - _mav_put_float(buf, 40, zmag); - _mav_put_float(buf, 44, abs_pressure); - _mav_put_float(buf, 48, diff_pressure); - _mav_put_float(buf, 52, pressure_alt); - _mav_put_float(buf, 56, temperature); - _mav_put_uint16_t(buf, 60, fields_updated); - _mav_put_uint8_t(buf, 62, id); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIGHRES_IMU, buf, MAVLINK_MSG_ID_HIGHRES_IMU_MIN_LEN, MAVLINK_MSG_ID_HIGHRES_IMU_LEN, MAVLINK_MSG_ID_HIGHRES_IMU_CRC); -#else - mavlink_highres_imu_t packet; - packet.time_usec = time_usec; - packet.xacc = xacc; - packet.yacc = yacc; - packet.zacc = zacc; - packet.xgyro = xgyro; - packet.ygyro = ygyro; - packet.zgyro = zgyro; - packet.xmag = xmag; - packet.ymag = ymag; - packet.zmag = zmag; - packet.abs_pressure = abs_pressure; - packet.diff_pressure = diff_pressure; - packet.pressure_alt = pressure_alt; - packet.temperature = temperature; - packet.fields_updated = fields_updated; - packet.id = id; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIGHRES_IMU, (const char *)&packet, MAVLINK_MSG_ID_HIGHRES_IMU_MIN_LEN, MAVLINK_MSG_ID_HIGHRES_IMU_LEN, MAVLINK_MSG_ID_HIGHRES_IMU_CRC); -#endif -} - -/** - * @brief Send a highres_imu message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_highres_imu_send_struct(mavlink_channel_t chan, const mavlink_highres_imu_t* highres_imu) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_highres_imu_send(chan, highres_imu->time_usec, highres_imu->xacc, highres_imu->yacc, highres_imu->zacc, highres_imu->xgyro, highres_imu->ygyro, highres_imu->zgyro, highres_imu->xmag, highres_imu->ymag, highres_imu->zmag, highres_imu->abs_pressure, highres_imu->diff_pressure, highres_imu->pressure_alt, highres_imu->temperature, highres_imu->fields_updated, highres_imu->id); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIGHRES_IMU, (const char *)highres_imu, MAVLINK_MSG_ID_HIGHRES_IMU_MIN_LEN, MAVLINK_MSG_ID_HIGHRES_IMU_LEN, MAVLINK_MSG_ID_HIGHRES_IMU_CRC); -#endif -} - -#if MAVLINK_MSG_ID_HIGHRES_IMU_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_highres_imu_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, float xacc, float yacc, float zacc, float xgyro, float ygyro, float zgyro, float xmag, float ymag, float zmag, float abs_pressure, float diff_pressure, float pressure_alt, float temperature, uint16_t fields_updated, uint8_t id) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, xacc); - _mav_put_float(buf, 12, yacc); - _mav_put_float(buf, 16, zacc); - _mav_put_float(buf, 20, xgyro); - _mav_put_float(buf, 24, ygyro); - _mav_put_float(buf, 28, zgyro); - _mav_put_float(buf, 32, xmag); - _mav_put_float(buf, 36, ymag); - _mav_put_float(buf, 40, zmag); - _mav_put_float(buf, 44, abs_pressure); - _mav_put_float(buf, 48, diff_pressure); - _mav_put_float(buf, 52, pressure_alt); - _mav_put_float(buf, 56, temperature); - _mav_put_uint16_t(buf, 60, fields_updated); - _mav_put_uint8_t(buf, 62, id); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIGHRES_IMU, buf, MAVLINK_MSG_ID_HIGHRES_IMU_MIN_LEN, MAVLINK_MSG_ID_HIGHRES_IMU_LEN, MAVLINK_MSG_ID_HIGHRES_IMU_CRC); -#else - mavlink_highres_imu_t *packet = (mavlink_highres_imu_t *)msgbuf; - packet->time_usec = time_usec; - packet->xacc = xacc; - packet->yacc = yacc; - packet->zacc = zacc; - packet->xgyro = xgyro; - packet->ygyro = ygyro; - packet->zgyro = zgyro; - packet->xmag = xmag; - packet->ymag = ymag; - packet->zmag = zmag; - packet->abs_pressure = abs_pressure; - packet->diff_pressure = diff_pressure; - packet->pressure_alt = pressure_alt; - packet->temperature = temperature; - packet->fields_updated = fields_updated; - packet->id = id; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIGHRES_IMU, (const char *)packet, MAVLINK_MSG_ID_HIGHRES_IMU_MIN_LEN, MAVLINK_MSG_ID_HIGHRES_IMU_LEN, MAVLINK_MSG_ID_HIGHRES_IMU_CRC); -#endif -} -#endif - -#endif - -// MESSAGE HIGHRES_IMU UNPACKING - - -/** - * @brief Get field time_usec from highres_imu message - * - * @return [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - */ -static inline uint64_t mavlink_msg_highres_imu_get_time_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field xacc from highres_imu message - * - * @return [m/s/s] X acceleration - */ -static inline float mavlink_msg_highres_imu_get_xacc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field yacc from highres_imu message - * - * @return [m/s/s] Y acceleration - */ -static inline float mavlink_msg_highres_imu_get_yacc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field zacc from highres_imu message - * - * @return [m/s/s] Z acceleration - */ -static inline float mavlink_msg_highres_imu_get_zacc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field xgyro from highres_imu message - * - * @return [rad/s] Angular speed around X axis - */ -static inline float mavlink_msg_highres_imu_get_xgyro(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Get field ygyro from highres_imu message - * - * @return [rad/s] Angular speed around Y axis - */ -static inline float mavlink_msg_highres_imu_get_ygyro(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Get field zgyro from highres_imu message - * - * @return [rad/s] Angular speed around Z axis - */ -static inline float mavlink_msg_highres_imu_get_zgyro(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 28); -} - -/** - * @brief Get field xmag from highres_imu message - * - * @return [gauss] X Magnetic field - */ -static inline float mavlink_msg_highres_imu_get_xmag(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 32); -} - -/** - * @brief Get field ymag from highres_imu message - * - * @return [gauss] Y Magnetic field - */ -static inline float mavlink_msg_highres_imu_get_ymag(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 36); -} - -/** - * @brief Get field zmag from highres_imu message - * - * @return [gauss] Z Magnetic field - */ -static inline float mavlink_msg_highres_imu_get_zmag(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 40); -} - -/** - * @brief Get field abs_pressure from highres_imu message - * - * @return [hPa] Absolute pressure - */ -static inline float mavlink_msg_highres_imu_get_abs_pressure(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 44); -} - -/** - * @brief Get field diff_pressure from highres_imu message - * - * @return [hPa] Differential pressure - */ -static inline float mavlink_msg_highres_imu_get_diff_pressure(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 48); -} - -/** - * @brief Get field pressure_alt from highres_imu message - * - * @return Altitude calculated from pressure - */ -static inline float mavlink_msg_highres_imu_get_pressure_alt(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 52); -} - -/** - * @brief Get field temperature from highres_imu message - * - * @return [degC] Temperature - */ -static inline float mavlink_msg_highres_imu_get_temperature(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 56); -} - -/** - * @brief Get field fields_updated from highres_imu message - * - * @return Bitmap for fields that have updated since last message - */ -static inline uint16_t mavlink_msg_highres_imu_get_fields_updated(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 60); -} - -/** - * @brief Get field id from highres_imu message - * - * @return Id. Ids are numbered from 0 and map to IMUs numbered from 1 (e.g. IMU1 will have a message with id=0) - */ -static inline uint8_t mavlink_msg_highres_imu_get_id(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 62); -} - -/** - * @brief Decode a highres_imu message into a struct - * - * @param msg The message to decode - * @param highres_imu C-struct to decode the message contents into - */ -static inline void mavlink_msg_highres_imu_decode(const mavlink_message_t* msg, mavlink_highres_imu_t* highres_imu) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - highres_imu->time_usec = mavlink_msg_highres_imu_get_time_usec(msg); - highres_imu->xacc = mavlink_msg_highres_imu_get_xacc(msg); - highres_imu->yacc = mavlink_msg_highres_imu_get_yacc(msg); - highres_imu->zacc = mavlink_msg_highres_imu_get_zacc(msg); - highres_imu->xgyro = mavlink_msg_highres_imu_get_xgyro(msg); - highres_imu->ygyro = mavlink_msg_highres_imu_get_ygyro(msg); - highres_imu->zgyro = mavlink_msg_highres_imu_get_zgyro(msg); - highres_imu->xmag = mavlink_msg_highres_imu_get_xmag(msg); - highres_imu->ymag = mavlink_msg_highres_imu_get_ymag(msg); - highres_imu->zmag = mavlink_msg_highres_imu_get_zmag(msg); - highres_imu->abs_pressure = mavlink_msg_highres_imu_get_abs_pressure(msg); - highres_imu->diff_pressure = mavlink_msg_highres_imu_get_diff_pressure(msg); - highres_imu->pressure_alt = mavlink_msg_highres_imu_get_pressure_alt(msg); - highres_imu->temperature = mavlink_msg_highres_imu_get_temperature(msg); - highres_imu->fields_updated = mavlink_msg_highres_imu_get_fields_updated(msg); - highres_imu->id = mavlink_msg_highres_imu_get_id(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_HIGHRES_IMU_LEN? msg->len : MAVLINK_MSG_ID_HIGHRES_IMU_LEN; - memset(highres_imu, 0, MAVLINK_MSG_ID_HIGHRES_IMU_LEN); - memcpy(highres_imu, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_hil_actuator_controls.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_hil_actuator_controls.h deleted file mode 100644 index 65f55821..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_hil_actuator_controls.h +++ /dev/null @@ -1,280 +0,0 @@ -#pragma once -// MESSAGE HIL_ACTUATOR_CONTROLS PACKING - -#define MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS 93 - - -typedef struct __mavlink_hil_actuator_controls_t { - uint64_t time_usec; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/ - uint64_t flags; /*< Flags as bitfield, 1: indicate simulation using lockstep.*/ - float controls[16]; /*< Control outputs -1 .. 1. Channel assignment depends on the simulated hardware.*/ - uint8_t mode; /*< System mode. Includes arming state.*/ -} mavlink_hil_actuator_controls_t; - -#define MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_LEN 81 -#define MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_MIN_LEN 81 -#define MAVLINK_MSG_ID_93_LEN 81 -#define MAVLINK_MSG_ID_93_MIN_LEN 81 - -#define MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_CRC 47 -#define MAVLINK_MSG_ID_93_CRC 47 - -#define MAVLINK_MSG_HIL_ACTUATOR_CONTROLS_FIELD_CONTROLS_LEN 16 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_HIL_ACTUATOR_CONTROLS { \ - 93, \ - "HIL_ACTUATOR_CONTROLS", \ - 4, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_actuator_controls_t, time_usec) }, \ - { "controls", NULL, MAVLINK_TYPE_FLOAT, 16, 16, offsetof(mavlink_hil_actuator_controls_t, controls) }, \ - { "mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 80, offsetof(mavlink_hil_actuator_controls_t, mode) }, \ - { "flags", NULL, MAVLINK_TYPE_UINT64_T, 0, 8, offsetof(mavlink_hil_actuator_controls_t, flags) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_HIL_ACTUATOR_CONTROLS { \ - "HIL_ACTUATOR_CONTROLS", \ - 4, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_actuator_controls_t, time_usec) }, \ - { "controls", NULL, MAVLINK_TYPE_FLOAT, 16, 16, offsetof(mavlink_hil_actuator_controls_t, controls) }, \ - { "mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 80, offsetof(mavlink_hil_actuator_controls_t, mode) }, \ - { "flags", NULL, MAVLINK_TYPE_UINT64_T, 0, 8, offsetof(mavlink_hil_actuator_controls_t, flags) }, \ - } \ -} -#endif - -/** - * @brief Pack a hil_actuator_controls message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @param controls Control outputs -1 .. 1. Channel assignment depends on the simulated hardware. - * @param mode System mode. Includes arming state. - * @param flags Flags as bitfield, 1: indicate simulation using lockstep. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_hil_actuator_controls_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint64_t time_usec, const float *controls, uint8_t mode, uint64_t flags) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint64_t(buf, 8, flags); - _mav_put_uint8_t(buf, 80, mode); - _mav_put_float_array(buf, 16, controls, 16); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_LEN); -#else - mavlink_hil_actuator_controls_t packet; - packet.time_usec = time_usec; - packet.flags = flags; - packet.mode = mode; - mav_array_memcpy(packet.controls, controls, sizeof(float)*16); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_MIN_LEN, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_LEN, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_CRC); -} - -/** - * @brief Pack a hil_actuator_controls message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @param controls Control outputs -1 .. 1. Channel assignment depends on the simulated hardware. - * @param mode System mode. Includes arming state. - * @param flags Flags as bitfield, 1: indicate simulation using lockstep. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_hil_actuator_controls_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint64_t time_usec,const float *controls,uint8_t mode,uint64_t flags) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint64_t(buf, 8, flags); - _mav_put_uint8_t(buf, 80, mode); - _mav_put_float_array(buf, 16, controls, 16); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_LEN); -#else - mavlink_hil_actuator_controls_t packet; - packet.time_usec = time_usec; - packet.flags = flags; - packet.mode = mode; - mav_array_memcpy(packet.controls, controls, sizeof(float)*16); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_MIN_LEN, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_LEN, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_CRC); -} - -/** - * @brief Encode a hil_actuator_controls struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param hil_actuator_controls C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_hil_actuator_controls_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_hil_actuator_controls_t* hil_actuator_controls) -{ - return mavlink_msg_hil_actuator_controls_pack(system_id, component_id, msg, hil_actuator_controls->time_usec, hil_actuator_controls->controls, hil_actuator_controls->mode, hil_actuator_controls->flags); -} - -/** - * @brief Encode a hil_actuator_controls struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param hil_actuator_controls C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_hil_actuator_controls_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_hil_actuator_controls_t* hil_actuator_controls) -{ - return mavlink_msg_hil_actuator_controls_pack_chan(system_id, component_id, chan, msg, hil_actuator_controls->time_usec, hil_actuator_controls->controls, hil_actuator_controls->mode, hil_actuator_controls->flags); -} - -/** - * @brief Send a hil_actuator_controls message - * @param chan MAVLink channel to send the message - * - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @param controls Control outputs -1 .. 1. Channel assignment depends on the simulated hardware. - * @param mode System mode. Includes arming state. - * @param flags Flags as bitfield, 1: indicate simulation using lockstep. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_hil_actuator_controls_send(mavlink_channel_t chan, uint64_t time_usec, const float *controls, uint8_t mode, uint64_t flags) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint64_t(buf, 8, flags); - _mav_put_uint8_t(buf, 80, mode); - _mav_put_float_array(buf, 16, controls, 16); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS, buf, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_MIN_LEN, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_LEN, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_CRC); -#else - mavlink_hil_actuator_controls_t packet; - packet.time_usec = time_usec; - packet.flags = flags; - packet.mode = mode; - mav_array_memcpy(packet.controls, controls, sizeof(float)*16); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS, (const char *)&packet, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_MIN_LEN, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_LEN, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_CRC); -#endif -} - -/** - * @brief Send a hil_actuator_controls message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_hil_actuator_controls_send_struct(mavlink_channel_t chan, const mavlink_hil_actuator_controls_t* hil_actuator_controls) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_hil_actuator_controls_send(chan, hil_actuator_controls->time_usec, hil_actuator_controls->controls, hil_actuator_controls->mode, hil_actuator_controls->flags); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS, (const char *)hil_actuator_controls, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_MIN_LEN, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_LEN, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_CRC); -#endif -} - -#if MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_hil_actuator_controls_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, const float *controls, uint8_t mode, uint64_t flags) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint64_t(buf, 8, flags); - _mav_put_uint8_t(buf, 80, mode); - _mav_put_float_array(buf, 16, controls, 16); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS, buf, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_MIN_LEN, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_LEN, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_CRC); -#else - mavlink_hil_actuator_controls_t *packet = (mavlink_hil_actuator_controls_t *)msgbuf; - packet->time_usec = time_usec; - packet->flags = flags; - packet->mode = mode; - mav_array_memcpy(packet->controls, controls, sizeof(float)*16); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS, (const char *)packet, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_MIN_LEN, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_LEN, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_CRC); -#endif -} -#endif - -#endif - -// MESSAGE HIL_ACTUATOR_CONTROLS UNPACKING - - -/** - * @brief Get field time_usec from hil_actuator_controls message - * - * @return [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - */ -static inline uint64_t mavlink_msg_hil_actuator_controls_get_time_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field controls from hil_actuator_controls message - * - * @return Control outputs -1 .. 1. Channel assignment depends on the simulated hardware. - */ -static inline uint16_t mavlink_msg_hil_actuator_controls_get_controls(const mavlink_message_t* msg, float *controls) -{ - return _MAV_RETURN_float_array(msg, controls, 16, 16); -} - -/** - * @brief Get field mode from hil_actuator_controls message - * - * @return System mode. Includes arming state. - */ -static inline uint8_t mavlink_msg_hil_actuator_controls_get_mode(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 80); -} - -/** - * @brief Get field flags from hil_actuator_controls message - * - * @return Flags as bitfield, 1: indicate simulation using lockstep. - */ -static inline uint64_t mavlink_msg_hil_actuator_controls_get_flags(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 8); -} - -/** - * @brief Decode a hil_actuator_controls message into a struct - * - * @param msg The message to decode - * @param hil_actuator_controls C-struct to decode the message contents into - */ -static inline void mavlink_msg_hil_actuator_controls_decode(const mavlink_message_t* msg, mavlink_hil_actuator_controls_t* hil_actuator_controls) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - hil_actuator_controls->time_usec = mavlink_msg_hil_actuator_controls_get_time_usec(msg); - hil_actuator_controls->flags = mavlink_msg_hil_actuator_controls_get_flags(msg); - mavlink_msg_hil_actuator_controls_get_controls(msg, hil_actuator_controls->controls); - hil_actuator_controls->mode = mavlink_msg_hil_actuator_controls_get_mode(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_LEN? msg->len : MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_LEN; - memset(hil_actuator_controls, 0, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_LEN); - memcpy(hil_actuator_controls, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_hil_controls.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_hil_controls.h deleted file mode 100644 index 8fc1c411..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_hil_controls.h +++ /dev/null @@ -1,463 +0,0 @@ -#pragma once -// MESSAGE HIL_CONTROLS PACKING - -#define MAVLINK_MSG_ID_HIL_CONTROLS 91 - - -typedef struct __mavlink_hil_controls_t { - uint64_t time_usec; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/ - float roll_ailerons; /*< Control output -1 .. 1*/ - float pitch_elevator; /*< Control output -1 .. 1*/ - float yaw_rudder; /*< Control output -1 .. 1*/ - float throttle; /*< Throttle 0 .. 1*/ - float aux1; /*< Aux 1, -1 .. 1*/ - float aux2; /*< Aux 2, -1 .. 1*/ - float aux3; /*< Aux 3, -1 .. 1*/ - float aux4; /*< Aux 4, -1 .. 1*/ - uint8_t mode; /*< System mode.*/ - uint8_t nav_mode; /*< Navigation mode (MAV_NAV_MODE)*/ -} mavlink_hil_controls_t; - -#define MAVLINK_MSG_ID_HIL_CONTROLS_LEN 42 -#define MAVLINK_MSG_ID_HIL_CONTROLS_MIN_LEN 42 -#define MAVLINK_MSG_ID_91_LEN 42 -#define MAVLINK_MSG_ID_91_MIN_LEN 42 - -#define MAVLINK_MSG_ID_HIL_CONTROLS_CRC 63 -#define MAVLINK_MSG_ID_91_CRC 63 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_HIL_CONTROLS { \ - 91, \ - "HIL_CONTROLS", \ - 11, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_controls_t, time_usec) }, \ - { "roll_ailerons", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_hil_controls_t, roll_ailerons) }, \ - { "pitch_elevator", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_hil_controls_t, pitch_elevator) }, \ - { "yaw_rudder", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_hil_controls_t, yaw_rudder) }, \ - { "throttle", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_hil_controls_t, throttle) }, \ - { "aux1", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_hil_controls_t, aux1) }, \ - { "aux2", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_hil_controls_t, aux2) }, \ - { "aux3", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_hil_controls_t, aux3) }, \ - { "aux4", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_hil_controls_t, aux4) }, \ - { "mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 40, offsetof(mavlink_hil_controls_t, mode) }, \ - { "nav_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 41, offsetof(mavlink_hil_controls_t, nav_mode) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_HIL_CONTROLS { \ - "HIL_CONTROLS", \ - 11, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_controls_t, time_usec) }, \ - { "roll_ailerons", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_hil_controls_t, roll_ailerons) }, \ - { "pitch_elevator", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_hil_controls_t, pitch_elevator) }, \ - { "yaw_rudder", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_hil_controls_t, yaw_rudder) }, \ - { "throttle", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_hil_controls_t, throttle) }, \ - { "aux1", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_hil_controls_t, aux1) }, \ - { "aux2", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_hil_controls_t, aux2) }, \ - { "aux3", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_hil_controls_t, aux3) }, \ - { "aux4", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_hil_controls_t, aux4) }, \ - { "mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 40, offsetof(mavlink_hil_controls_t, mode) }, \ - { "nav_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 41, offsetof(mavlink_hil_controls_t, nav_mode) }, \ - } \ -} -#endif - -/** - * @brief Pack a hil_controls message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @param roll_ailerons Control output -1 .. 1 - * @param pitch_elevator Control output -1 .. 1 - * @param yaw_rudder Control output -1 .. 1 - * @param throttle Throttle 0 .. 1 - * @param aux1 Aux 1, -1 .. 1 - * @param aux2 Aux 2, -1 .. 1 - * @param aux3 Aux 3, -1 .. 1 - * @param aux4 Aux 4, -1 .. 1 - * @param mode System mode. - * @param nav_mode Navigation mode (MAV_NAV_MODE) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_hil_controls_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint64_t time_usec, float roll_ailerons, float pitch_elevator, float yaw_rudder, float throttle, float aux1, float aux2, float aux3, float aux4, uint8_t mode, uint8_t nav_mode) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_HIL_CONTROLS_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, roll_ailerons); - _mav_put_float(buf, 12, pitch_elevator); - _mav_put_float(buf, 16, yaw_rudder); - _mav_put_float(buf, 20, throttle); - _mav_put_float(buf, 24, aux1); - _mav_put_float(buf, 28, aux2); - _mav_put_float(buf, 32, aux3); - _mav_put_float(buf, 36, aux4); - _mav_put_uint8_t(buf, 40, mode); - _mav_put_uint8_t(buf, 41, nav_mode); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIL_CONTROLS_LEN); -#else - mavlink_hil_controls_t packet; - packet.time_usec = time_usec; - packet.roll_ailerons = roll_ailerons; - packet.pitch_elevator = pitch_elevator; - packet.yaw_rudder = yaw_rudder; - packet.throttle = throttle; - packet.aux1 = aux1; - packet.aux2 = aux2; - packet.aux3 = aux3; - packet.aux4 = aux4; - packet.mode = mode; - packet.nav_mode = nav_mode; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIL_CONTROLS_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_HIL_CONTROLS; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HIL_CONTROLS_MIN_LEN, MAVLINK_MSG_ID_HIL_CONTROLS_LEN, MAVLINK_MSG_ID_HIL_CONTROLS_CRC); -} - -/** - * @brief Pack a hil_controls message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @param roll_ailerons Control output -1 .. 1 - * @param pitch_elevator Control output -1 .. 1 - * @param yaw_rudder Control output -1 .. 1 - * @param throttle Throttle 0 .. 1 - * @param aux1 Aux 1, -1 .. 1 - * @param aux2 Aux 2, -1 .. 1 - * @param aux3 Aux 3, -1 .. 1 - * @param aux4 Aux 4, -1 .. 1 - * @param mode System mode. - * @param nav_mode Navigation mode (MAV_NAV_MODE) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_hil_controls_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint64_t time_usec,float roll_ailerons,float pitch_elevator,float yaw_rudder,float throttle,float aux1,float aux2,float aux3,float aux4,uint8_t mode,uint8_t nav_mode) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_HIL_CONTROLS_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, roll_ailerons); - _mav_put_float(buf, 12, pitch_elevator); - _mav_put_float(buf, 16, yaw_rudder); - _mav_put_float(buf, 20, throttle); - _mav_put_float(buf, 24, aux1); - _mav_put_float(buf, 28, aux2); - _mav_put_float(buf, 32, aux3); - _mav_put_float(buf, 36, aux4); - _mav_put_uint8_t(buf, 40, mode); - _mav_put_uint8_t(buf, 41, nav_mode); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIL_CONTROLS_LEN); -#else - mavlink_hil_controls_t packet; - packet.time_usec = time_usec; - packet.roll_ailerons = roll_ailerons; - packet.pitch_elevator = pitch_elevator; - packet.yaw_rudder = yaw_rudder; - packet.throttle = throttle; - packet.aux1 = aux1; - packet.aux2 = aux2; - packet.aux3 = aux3; - packet.aux4 = aux4; - packet.mode = mode; - packet.nav_mode = nav_mode; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIL_CONTROLS_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_HIL_CONTROLS; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HIL_CONTROLS_MIN_LEN, MAVLINK_MSG_ID_HIL_CONTROLS_LEN, MAVLINK_MSG_ID_HIL_CONTROLS_CRC); -} - -/** - * @brief Encode a hil_controls struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param hil_controls C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_hil_controls_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_hil_controls_t* hil_controls) -{ - return mavlink_msg_hil_controls_pack(system_id, component_id, msg, hil_controls->time_usec, hil_controls->roll_ailerons, hil_controls->pitch_elevator, hil_controls->yaw_rudder, hil_controls->throttle, hil_controls->aux1, hil_controls->aux2, hil_controls->aux3, hil_controls->aux4, hil_controls->mode, hil_controls->nav_mode); -} - -/** - * @brief Encode a hil_controls struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param hil_controls C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_hil_controls_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_hil_controls_t* hil_controls) -{ - return mavlink_msg_hil_controls_pack_chan(system_id, component_id, chan, msg, hil_controls->time_usec, hil_controls->roll_ailerons, hil_controls->pitch_elevator, hil_controls->yaw_rudder, hil_controls->throttle, hil_controls->aux1, hil_controls->aux2, hil_controls->aux3, hil_controls->aux4, hil_controls->mode, hil_controls->nav_mode); -} - -/** - * @brief Send a hil_controls message - * @param chan MAVLink channel to send the message - * - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @param roll_ailerons Control output -1 .. 1 - * @param pitch_elevator Control output -1 .. 1 - * @param yaw_rudder Control output -1 .. 1 - * @param throttle Throttle 0 .. 1 - * @param aux1 Aux 1, -1 .. 1 - * @param aux2 Aux 2, -1 .. 1 - * @param aux3 Aux 3, -1 .. 1 - * @param aux4 Aux 4, -1 .. 1 - * @param mode System mode. - * @param nav_mode Navigation mode (MAV_NAV_MODE) - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_hil_controls_send(mavlink_channel_t chan, uint64_t time_usec, float roll_ailerons, float pitch_elevator, float yaw_rudder, float throttle, float aux1, float aux2, float aux3, float aux4, uint8_t mode, uint8_t nav_mode) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_HIL_CONTROLS_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, roll_ailerons); - _mav_put_float(buf, 12, pitch_elevator); - _mav_put_float(buf, 16, yaw_rudder); - _mav_put_float(buf, 20, throttle); - _mav_put_float(buf, 24, aux1); - _mav_put_float(buf, 28, aux2); - _mav_put_float(buf, 32, aux3); - _mav_put_float(buf, 36, aux4); - _mav_put_uint8_t(buf, 40, mode); - _mav_put_uint8_t(buf, 41, nav_mode); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_CONTROLS, buf, MAVLINK_MSG_ID_HIL_CONTROLS_MIN_LEN, MAVLINK_MSG_ID_HIL_CONTROLS_LEN, MAVLINK_MSG_ID_HIL_CONTROLS_CRC); -#else - mavlink_hil_controls_t packet; - packet.time_usec = time_usec; - packet.roll_ailerons = roll_ailerons; - packet.pitch_elevator = pitch_elevator; - packet.yaw_rudder = yaw_rudder; - packet.throttle = throttle; - packet.aux1 = aux1; - packet.aux2 = aux2; - packet.aux3 = aux3; - packet.aux4 = aux4; - packet.mode = mode; - packet.nav_mode = nav_mode; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_CONTROLS, (const char *)&packet, MAVLINK_MSG_ID_HIL_CONTROLS_MIN_LEN, MAVLINK_MSG_ID_HIL_CONTROLS_LEN, MAVLINK_MSG_ID_HIL_CONTROLS_CRC); -#endif -} - -/** - * @brief Send a hil_controls message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_hil_controls_send_struct(mavlink_channel_t chan, const mavlink_hil_controls_t* hil_controls) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_hil_controls_send(chan, hil_controls->time_usec, hil_controls->roll_ailerons, hil_controls->pitch_elevator, hil_controls->yaw_rudder, hil_controls->throttle, hil_controls->aux1, hil_controls->aux2, hil_controls->aux3, hil_controls->aux4, hil_controls->mode, hil_controls->nav_mode); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_CONTROLS, (const char *)hil_controls, MAVLINK_MSG_ID_HIL_CONTROLS_MIN_LEN, MAVLINK_MSG_ID_HIL_CONTROLS_LEN, MAVLINK_MSG_ID_HIL_CONTROLS_CRC); -#endif -} - -#if MAVLINK_MSG_ID_HIL_CONTROLS_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_hil_controls_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, float roll_ailerons, float pitch_elevator, float yaw_rudder, float throttle, float aux1, float aux2, float aux3, float aux4, uint8_t mode, uint8_t nav_mode) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, roll_ailerons); - _mav_put_float(buf, 12, pitch_elevator); - _mav_put_float(buf, 16, yaw_rudder); - _mav_put_float(buf, 20, throttle); - _mav_put_float(buf, 24, aux1); - _mav_put_float(buf, 28, aux2); - _mav_put_float(buf, 32, aux3); - _mav_put_float(buf, 36, aux4); - _mav_put_uint8_t(buf, 40, mode); - _mav_put_uint8_t(buf, 41, nav_mode); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_CONTROLS, buf, MAVLINK_MSG_ID_HIL_CONTROLS_MIN_LEN, MAVLINK_MSG_ID_HIL_CONTROLS_LEN, MAVLINK_MSG_ID_HIL_CONTROLS_CRC); -#else - mavlink_hil_controls_t *packet = (mavlink_hil_controls_t *)msgbuf; - packet->time_usec = time_usec; - packet->roll_ailerons = roll_ailerons; - packet->pitch_elevator = pitch_elevator; - packet->yaw_rudder = yaw_rudder; - packet->throttle = throttle; - packet->aux1 = aux1; - packet->aux2 = aux2; - packet->aux3 = aux3; - packet->aux4 = aux4; - packet->mode = mode; - packet->nav_mode = nav_mode; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_CONTROLS, (const char *)packet, MAVLINK_MSG_ID_HIL_CONTROLS_MIN_LEN, MAVLINK_MSG_ID_HIL_CONTROLS_LEN, MAVLINK_MSG_ID_HIL_CONTROLS_CRC); -#endif -} -#endif - -#endif - -// MESSAGE HIL_CONTROLS UNPACKING - - -/** - * @brief Get field time_usec from hil_controls message - * - * @return [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - */ -static inline uint64_t mavlink_msg_hil_controls_get_time_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field roll_ailerons from hil_controls message - * - * @return Control output -1 .. 1 - */ -static inline float mavlink_msg_hil_controls_get_roll_ailerons(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field pitch_elevator from hil_controls message - * - * @return Control output -1 .. 1 - */ -static inline float mavlink_msg_hil_controls_get_pitch_elevator(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field yaw_rudder from hil_controls message - * - * @return Control output -1 .. 1 - */ -static inline float mavlink_msg_hil_controls_get_yaw_rudder(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field throttle from hil_controls message - * - * @return Throttle 0 .. 1 - */ -static inline float mavlink_msg_hil_controls_get_throttle(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Get field aux1 from hil_controls message - * - * @return Aux 1, -1 .. 1 - */ -static inline float mavlink_msg_hil_controls_get_aux1(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Get field aux2 from hil_controls message - * - * @return Aux 2, -1 .. 1 - */ -static inline float mavlink_msg_hil_controls_get_aux2(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 28); -} - -/** - * @brief Get field aux3 from hil_controls message - * - * @return Aux 3, -1 .. 1 - */ -static inline float mavlink_msg_hil_controls_get_aux3(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 32); -} - -/** - * @brief Get field aux4 from hil_controls message - * - * @return Aux 4, -1 .. 1 - */ -static inline float mavlink_msg_hil_controls_get_aux4(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 36); -} - -/** - * @brief Get field mode from hil_controls message - * - * @return System mode. - */ -static inline uint8_t mavlink_msg_hil_controls_get_mode(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 40); -} - -/** - * @brief Get field nav_mode from hil_controls message - * - * @return Navigation mode (MAV_NAV_MODE) - */ -static inline uint8_t mavlink_msg_hil_controls_get_nav_mode(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 41); -} - -/** - * @brief Decode a hil_controls message into a struct - * - * @param msg The message to decode - * @param hil_controls C-struct to decode the message contents into - */ -static inline void mavlink_msg_hil_controls_decode(const mavlink_message_t* msg, mavlink_hil_controls_t* hil_controls) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - hil_controls->time_usec = mavlink_msg_hil_controls_get_time_usec(msg); - hil_controls->roll_ailerons = mavlink_msg_hil_controls_get_roll_ailerons(msg); - hil_controls->pitch_elevator = mavlink_msg_hil_controls_get_pitch_elevator(msg); - hil_controls->yaw_rudder = mavlink_msg_hil_controls_get_yaw_rudder(msg); - hil_controls->throttle = mavlink_msg_hil_controls_get_throttle(msg); - hil_controls->aux1 = mavlink_msg_hil_controls_get_aux1(msg); - hil_controls->aux2 = mavlink_msg_hil_controls_get_aux2(msg); - hil_controls->aux3 = mavlink_msg_hil_controls_get_aux3(msg); - hil_controls->aux4 = mavlink_msg_hil_controls_get_aux4(msg); - hil_controls->mode = mavlink_msg_hil_controls_get_mode(msg); - hil_controls->nav_mode = mavlink_msg_hil_controls_get_nav_mode(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_HIL_CONTROLS_LEN? msg->len : MAVLINK_MSG_ID_HIL_CONTROLS_LEN; - memset(hil_controls, 0, MAVLINK_MSG_ID_HIL_CONTROLS_LEN); - memcpy(hil_controls, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_hil_gps.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_hil_gps.h deleted file mode 100644 index aa198380..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_hil_gps.h +++ /dev/null @@ -1,563 +0,0 @@ -#pragma once -// MESSAGE HIL_GPS PACKING - -#define MAVLINK_MSG_ID_HIL_GPS 113 - -MAVPACKED( -typedef struct __mavlink_hil_gps_t { - uint64_t time_usec; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/ - int32_t lat; /*< [degE7] Latitude (WGS84)*/ - int32_t lon; /*< [degE7] Longitude (WGS84)*/ - int32_t alt; /*< [mm] Altitude (MSL). Positive for up.*/ - uint16_t eph; /*< GPS HDOP horizontal dilution of position (unitless * 100). If unknown, set to: UINT16_MAX*/ - uint16_t epv; /*< GPS VDOP vertical dilution of position (unitless * 100). If unknown, set to: UINT16_MAX*/ - uint16_t vel; /*< [cm/s] GPS ground speed. If unknown, set to: UINT16_MAX*/ - int16_t vn; /*< [cm/s] GPS velocity in north direction in earth-fixed NED frame*/ - int16_t ve; /*< [cm/s] GPS velocity in east direction in earth-fixed NED frame*/ - int16_t vd; /*< [cm/s] GPS velocity in down direction in earth-fixed NED frame*/ - uint16_t cog; /*< [cdeg] Course over ground (NOT heading, but direction of movement), 0.0..359.99 degrees. If unknown, set to: UINT16_MAX*/ - uint8_t fix_type; /*< 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix.*/ - uint8_t satellites_visible; /*< Number of satellites visible. If unknown, set to UINT8_MAX*/ - uint8_t id; /*< GPS ID (zero indexed). Used for multiple GPS inputs*/ - uint16_t yaw; /*< [cdeg] Yaw of vehicle relative to Earth's North, zero means not available, use 36000 for north*/ -}) mavlink_hil_gps_t; - -#define MAVLINK_MSG_ID_HIL_GPS_LEN 39 -#define MAVLINK_MSG_ID_HIL_GPS_MIN_LEN 36 -#define MAVLINK_MSG_ID_113_LEN 39 -#define MAVLINK_MSG_ID_113_MIN_LEN 36 - -#define MAVLINK_MSG_ID_HIL_GPS_CRC 124 -#define MAVLINK_MSG_ID_113_CRC 124 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_HIL_GPS { \ - 113, \ - "HIL_GPS", \ - 15, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_gps_t, time_usec) }, \ - { "fix_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_hil_gps_t, fix_type) }, \ - { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_hil_gps_t, lat) }, \ - { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_hil_gps_t, lon) }, \ - { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_hil_gps_t, alt) }, \ - { "eph", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_hil_gps_t, eph) }, \ - { "epv", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_hil_gps_t, epv) }, \ - { "vel", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_hil_gps_t, vel) }, \ - { "vn", NULL, MAVLINK_TYPE_INT16_T, 0, 26, offsetof(mavlink_hil_gps_t, vn) }, \ - { "ve", NULL, MAVLINK_TYPE_INT16_T, 0, 28, offsetof(mavlink_hil_gps_t, ve) }, \ - { "vd", NULL, MAVLINK_TYPE_INT16_T, 0, 30, offsetof(mavlink_hil_gps_t, vd) }, \ - { "cog", NULL, MAVLINK_TYPE_UINT16_T, 0, 32, offsetof(mavlink_hil_gps_t, cog) }, \ - { "satellites_visible", NULL, MAVLINK_TYPE_UINT8_T, 0, 35, offsetof(mavlink_hil_gps_t, satellites_visible) }, \ - { "id", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_hil_gps_t, id) }, \ - { "yaw", NULL, MAVLINK_TYPE_UINT16_T, 0, 37, offsetof(mavlink_hil_gps_t, yaw) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_HIL_GPS { \ - "HIL_GPS", \ - 15, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_gps_t, time_usec) }, \ - { "fix_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_hil_gps_t, fix_type) }, \ - { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_hil_gps_t, lat) }, \ - { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_hil_gps_t, lon) }, \ - { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_hil_gps_t, alt) }, \ - { "eph", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_hil_gps_t, eph) }, \ - { "epv", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_hil_gps_t, epv) }, \ - { "vel", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_hil_gps_t, vel) }, \ - { "vn", NULL, MAVLINK_TYPE_INT16_T, 0, 26, offsetof(mavlink_hil_gps_t, vn) }, \ - { "ve", NULL, MAVLINK_TYPE_INT16_T, 0, 28, offsetof(mavlink_hil_gps_t, ve) }, \ - { "vd", NULL, MAVLINK_TYPE_INT16_T, 0, 30, offsetof(mavlink_hil_gps_t, vd) }, \ - { "cog", NULL, MAVLINK_TYPE_UINT16_T, 0, 32, offsetof(mavlink_hil_gps_t, cog) }, \ - { "satellites_visible", NULL, MAVLINK_TYPE_UINT8_T, 0, 35, offsetof(mavlink_hil_gps_t, satellites_visible) }, \ - { "id", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_hil_gps_t, id) }, \ - { "yaw", NULL, MAVLINK_TYPE_UINT16_T, 0, 37, offsetof(mavlink_hil_gps_t, yaw) }, \ - } \ -} -#endif - -/** - * @brief Pack a hil_gps message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. - * @param lat [degE7] Latitude (WGS84) - * @param lon [degE7] Longitude (WGS84) - * @param alt [mm] Altitude (MSL). Positive for up. - * @param eph GPS HDOP horizontal dilution of position (unitless * 100). If unknown, set to: UINT16_MAX - * @param epv GPS VDOP vertical dilution of position (unitless * 100). If unknown, set to: UINT16_MAX - * @param vel [cm/s] GPS ground speed. If unknown, set to: UINT16_MAX - * @param vn [cm/s] GPS velocity in north direction in earth-fixed NED frame - * @param ve [cm/s] GPS velocity in east direction in earth-fixed NED frame - * @param vd [cm/s] GPS velocity in down direction in earth-fixed NED frame - * @param cog [cdeg] Course over ground (NOT heading, but direction of movement), 0.0..359.99 degrees. If unknown, set to: UINT16_MAX - * @param satellites_visible Number of satellites visible. If unknown, set to UINT8_MAX - * @param id GPS ID (zero indexed). Used for multiple GPS inputs - * @param yaw [cdeg] Yaw of vehicle relative to Earth's North, zero means not available, use 36000 for north - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_hil_gps_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint64_t time_usec, uint8_t fix_type, int32_t lat, int32_t lon, int32_t alt, uint16_t eph, uint16_t epv, uint16_t vel, int16_t vn, int16_t ve, int16_t vd, uint16_t cog, uint8_t satellites_visible, uint8_t id, uint16_t yaw) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_HIL_GPS_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_int32_t(buf, 8, lat); - _mav_put_int32_t(buf, 12, lon); - _mav_put_int32_t(buf, 16, alt); - _mav_put_uint16_t(buf, 20, eph); - _mav_put_uint16_t(buf, 22, epv); - _mav_put_uint16_t(buf, 24, vel); - _mav_put_int16_t(buf, 26, vn); - _mav_put_int16_t(buf, 28, ve); - _mav_put_int16_t(buf, 30, vd); - _mav_put_uint16_t(buf, 32, cog); - _mav_put_uint8_t(buf, 34, fix_type); - _mav_put_uint8_t(buf, 35, satellites_visible); - _mav_put_uint8_t(buf, 36, id); - _mav_put_uint16_t(buf, 37, yaw); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIL_GPS_LEN); -#else - mavlink_hil_gps_t packet; - packet.time_usec = time_usec; - packet.lat = lat; - packet.lon = lon; - packet.alt = alt; - packet.eph = eph; - packet.epv = epv; - packet.vel = vel; - packet.vn = vn; - packet.ve = ve; - packet.vd = vd; - packet.cog = cog; - packet.fix_type = fix_type; - packet.satellites_visible = satellites_visible; - packet.id = id; - packet.yaw = yaw; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIL_GPS_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_HIL_GPS; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HIL_GPS_MIN_LEN, MAVLINK_MSG_ID_HIL_GPS_LEN, MAVLINK_MSG_ID_HIL_GPS_CRC); -} - -/** - * @brief Pack a hil_gps message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. - * @param lat [degE7] Latitude (WGS84) - * @param lon [degE7] Longitude (WGS84) - * @param alt [mm] Altitude (MSL). Positive for up. - * @param eph GPS HDOP horizontal dilution of position (unitless * 100). If unknown, set to: UINT16_MAX - * @param epv GPS VDOP vertical dilution of position (unitless * 100). If unknown, set to: UINT16_MAX - * @param vel [cm/s] GPS ground speed. If unknown, set to: UINT16_MAX - * @param vn [cm/s] GPS velocity in north direction in earth-fixed NED frame - * @param ve [cm/s] GPS velocity in east direction in earth-fixed NED frame - * @param vd [cm/s] GPS velocity in down direction in earth-fixed NED frame - * @param cog [cdeg] Course over ground (NOT heading, but direction of movement), 0.0..359.99 degrees. If unknown, set to: UINT16_MAX - * @param satellites_visible Number of satellites visible. If unknown, set to UINT8_MAX - * @param id GPS ID (zero indexed). Used for multiple GPS inputs - * @param yaw [cdeg] Yaw of vehicle relative to Earth's North, zero means not available, use 36000 for north - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_hil_gps_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint64_t time_usec,uint8_t fix_type,int32_t lat,int32_t lon,int32_t alt,uint16_t eph,uint16_t epv,uint16_t vel,int16_t vn,int16_t ve,int16_t vd,uint16_t cog,uint8_t satellites_visible,uint8_t id,uint16_t yaw) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_HIL_GPS_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_int32_t(buf, 8, lat); - _mav_put_int32_t(buf, 12, lon); - _mav_put_int32_t(buf, 16, alt); - _mav_put_uint16_t(buf, 20, eph); - _mav_put_uint16_t(buf, 22, epv); - _mav_put_uint16_t(buf, 24, vel); - _mav_put_int16_t(buf, 26, vn); - _mav_put_int16_t(buf, 28, ve); - _mav_put_int16_t(buf, 30, vd); - _mav_put_uint16_t(buf, 32, cog); - _mav_put_uint8_t(buf, 34, fix_type); - _mav_put_uint8_t(buf, 35, satellites_visible); - _mav_put_uint8_t(buf, 36, id); - _mav_put_uint16_t(buf, 37, yaw); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIL_GPS_LEN); -#else - mavlink_hil_gps_t packet; - packet.time_usec = time_usec; - packet.lat = lat; - packet.lon = lon; - packet.alt = alt; - packet.eph = eph; - packet.epv = epv; - packet.vel = vel; - packet.vn = vn; - packet.ve = ve; - packet.vd = vd; - packet.cog = cog; - packet.fix_type = fix_type; - packet.satellites_visible = satellites_visible; - packet.id = id; - packet.yaw = yaw; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIL_GPS_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_HIL_GPS; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HIL_GPS_MIN_LEN, MAVLINK_MSG_ID_HIL_GPS_LEN, MAVLINK_MSG_ID_HIL_GPS_CRC); -} - -/** - * @brief Encode a hil_gps struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param hil_gps C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_hil_gps_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_hil_gps_t* hil_gps) -{ - return mavlink_msg_hil_gps_pack(system_id, component_id, msg, hil_gps->time_usec, hil_gps->fix_type, hil_gps->lat, hil_gps->lon, hil_gps->alt, hil_gps->eph, hil_gps->epv, hil_gps->vel, hil_gps->vn, hil_gps->ve, hil_gps->vd, hil_gps->cog, hil_gps->satellites_visible, hil_gps->id, hil_gps->yaw); -} - -/** - * @brief Encode a hil_gps struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param hil_gps C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_hil_gps_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_hil_gps_t* hil_gps) -{ - return mavlink_msg_hil_gps_pack_chan(system_id, component_id, chan, msg, hil_gps->time_usec, hil_gps->fix_type, hil_gps->lat, hil_gps->lon, hil_gps->alt, hil_gps->eph, hil_gps->epv, hil_gps->vel, hil_gps->vn, hil_gps->ve, hil_gps->vd, hil_gps->cog, hil_gps->satellites_visible, hil_gps->id, hil_gps->yaw); -} - -/** - * @brief Send a hil_gps message - * @param chan MAVLink channel to send the message - * - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. - * @param lat [degE7] Latitude (WGS84) - * @param lon [degE7] Longitude (WGS84) - * @param alt [mm] Altitude (MSL). Positive for up. - * @param eph GPS HDOP horizontal dilution of position (unitless * 100). If unknown, set to: UINT16_MAX - * @param epv GPS VDOP vertical dilution of position (unitless * 100). If unknown, set to: UINT16_MAX - * @param vel [cm/s] GPS ground speed. If unknown, set to: UINT16_MAX - * @param vn [cm/s] GPS velocity in north direction in earth-fixed NED frame - * @param ve [cm/s] GPS velocity in east direction in earth-fixed NED frame - * @param vd [cm/s] GPS velocity in down direction in earth-fixed NED frame - * @param cog [cdeg] Course over ground (NOT heading, but direction of movement), 0.0..359.99 degrees. If unknown, set to: UINT16_MAX - * @param satellites_visible Number of satellites visible. If unknown, set to UINT8_MAX - * @param id GPS ID (zero indexed). Used for multiple GPS inputs - * @param yaw [cdeg] Yaw of vehicle relative to Earth's North, zero means not available, use 36000 for north - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_hil_gps_send(mavlink_channel_t chan, uint64_t time_usec, uint8_t fix_type, int32_t lat, int32_t lon, int32_t alt, uint16_t eph, uint16_t epv, uint16_t vel, int16_t vn, int16_t ve, int16_t vd, uint16_t cog, uint8_t satellites_visible, uint8_t id, uint16_t yaw) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_HIL_GPS_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_int32_t(buf, 8, lat); - _mav_put_int32_t(buf, 12, lon); - _mav_put_int32_t(buf, 16, alt); - _mav_put_uint16_t(buf, 20, eph); - _mav_put_uint16_t(buf, 22, epv); - _mav_put_uint16_t(buf, 24, vel); - _mav_put_int16_t(buf, 26, vn); - _mav_put_int16_t(buf, 28, ve); - _mav_put_int16_t(buf, 30, vd); - _mav_put_uint16_t(buf, 32, cog); - _mav_put_uint8_t(buf, 34, fix_type); - _mav_put_uint8_t(buf, 35, satellites_visible); - _mav_put_uint8_t(buf, 36, id); - _mav_put_uint16_t(buf, 37, yaw); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_GPS, buf, MAVLINK_MSG_ID_HIL_GPS_MIN_LEN, MAVLINK_MSG_ID_HIL_GPS_LEN, MAVLINK_MSG_ID_HIL_GPS_CRC); -#else - mavlink_hil_gps_t packet; - packet.time_usec = time_usec; - packet.lat = lat; - packet.lon = lon; - packet.alt = alt; - packet.eph = eph; - packet.epv = epv; - packet.vel = vel; - packet.vn = vn; - packet.ve = ve; - packet.vd = vd; - packet.cog = cog; - packet.fix_type = fix_type; - packet.satellites_visible = satellites_visible; - packet.id = id; - packet.yaw = yaw; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_GPS, (const char *)&packet, MAVLINK_MSG_ID_HIL_GPS_MIN_LEN, MAVLINK_MSG_ID_HIL_GPS_LEN, MAVLINK_MSG_ID_HIL_GPS_CRC); -#endif -} - -/** - * @brief Send a hil_gps message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_hil_gps_send_struct(mavlink_channel_t chan, const mavlink_hil_gps_t* hil_gps) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_hil_gps_send(chan, hil_gps->time_usec, hil_gps->fix_type, hil_gps->lat, hil_gps->lon, hil_gps->alt, hil_gps->eph, hil_gps->epv, hil_gps->vel, hil_gps->vn, hil_gps->ve, hil_gps->vd, hil_gps->cog, hil_gps->satellites_visible, hil_gps->id, hil_gps->yaw); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_GPS, (const char *)hil_gps, MAVLINK_MSG_ID_HIL_GPS_MIN_LEN, MAVLINK_MSG_ID_HIL_GPS_LEN, MAVLINK_MSG_ID_HIL_GPS_CRC); -#endif -} - -#if MAVLINK_MSG_ID_HIL_GPS_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_hil_gps_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, uint8_t fix_type, int32_t lat, int32_t lon, int32_t alt, uint16_t eph, uint16_t epv, uint16_t vel, int16_t vn, int16_t ve, int16_t vd, uint16_t cog, uint8_t satellites_visible, uint8_t id, uint16_t yaw) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_int32_t(buf, 8, lat); - _mav_put_int32_t(buf, 12, lon); - _mav_put_int32_t(buf, 16, alt); - _mav_put_uint16_t(buf, 20, eph); - _mav_put_uint16_t(buf, 22, epv); - _mav_put_uint16_t(buf, 24, vel); - _mav_put_int16_t(buf, 26, vn); - _mav_put_int16_t(buf, 28, ve); - _mav_put_int16_t(buf, 30, vd); - _mav_put_uint16_t(buf, 32, cog); - _mav_put_uint8_t(buf, 34, fix_type); - _mav_put_uint8_t(buf, 35, satellites_visible); - _mav_put_uint8_t(buf, 36, id); - _mav_put_uint16_t(buf, 37, yaw); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_GPS, buf, MAVLINK_MSG_ID_HIL_GPS_MIN_LEN, MAVLINK_MSG_ID_HIL_GPS_LEN, MAVLINK_MSG_ID_HIL_GPS_CRC); -#else - mavlink_hil_gps_t *packet = (mavlink_hil_gps_t *)msgbuf; - packet->time_usec = time_usec; - packet->lat = lat; - packet->lon = lon; - packet->alt = alt; - packet->eph = eph; - packet->epv = epv; - packet->vel = vel; - packet->vn = vn; - packet->ve = ve; - packet->vd = vd; - packet->cog = cog; - packet->fix_type = fix_type; - packet->satellites_visible = satellites_visible; - packet->id = id; - packet->yaw = yaw; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_GPS, (const char *)packet, MAVLINK_MSG_ID_HIL_GPS_MIN_LEN, MAVLINK_MSG_ID_HIL_GPS_LEN, MAVLINK_MSG_ID_HIL_GPS_CRC); -#endif -} -#endif - -#endif - -// MESSAGE HIL_GPS UNPACKING - - -/** - * @brief Get field time_usec from hil_gps message - * - * @return [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - */ -static inline uint64_t mavlink_msg_hil_gps_get_time_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field fix_type from hil_gps message - * - * @return 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. - */ -static inline uint8_t mavlink_msg_hil_gps_get_fix_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 34); -} - -/** - * @brief Get field lat from hil_gps message - * - * @return [degE7] Latitude (WGS84) - */ -static inline int32_t mavlink_msg_hil_gps_get_lat(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 8); -} - -/** - * @brief Get field lon from hil_gps message - * - * @return [degE7] Longitude (WGS84) - */ -static inline int32_t mavlink_msg_hil_gps_get_lon(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 12); -} - -/** - * @brief Get field alt from hil_gps message - * - * @return [mm] Altitude (MSL). Positive for up. - */ -static inline int32_t mavlink_msg_hil_gps_get_alt(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 16); -} - -/** - * @brief Get field eph from hil_gps message - * - * @return GPS HDOP horizontal dilution of position (unitless * 100). If unknown, set to: UINT16_MAX - */ -static inline uint16_t mavlink_msg_hil_gps_get_eph(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 20); -} - -/** - * @brief Get field epv from hil_gps message - * - * @return GPS VDOP vertical dilution of position (unitless * 100). If unknown, set to: UINT16_MAX - */ -static inline uint16_t mavlink_msg_hil_gps_get_epv(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 22); -} - -/** - * @brief Get field vel from hil_gps message - * - * @return [cm/s] GPS ground speed. If unknown, set to: UINT16_MAX - */ -static inline uint16_t mavlink_msg_hil_gps_get_vel(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 24); -} - -/** - * @brief Get field vn from hil_gps message - * - * @return [cm/s] GPS velocity in north direction in earth-fixed NED frame - */ -static inline int16_t mavlink_msg_hil_gps_get_vn(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 26); -} - -/** - * @brief Get field ve from hil_gps message - * - * @return [cm/s] GPS velocity in east direction in earth-fixed NED frame - */ -static inline int16_t mavlink_msg_hil_gps_get_ve(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 28); -} - -/** - * @brief Get field vd from hil_gps message - * - * @return [cm/s] GPS velocity in down direction in earth-fixed NED frame - */ -static inline int16_t mavlink_msg_hil_gps_get_vd(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 30); -} - -/** - * @brief Get field cog from hil_gps message - * - * @return [cdeg] Course over ground (NOT heading, but direction of movement), 0.0..359.99 degrees. If unknown, set to: UINT16_MAX - */ -static inline uint16_t mavlink_msg_hil_gps_get_cog(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 32); -} - -/** - * @brief Get field satellites_visible from hil_gps message - * - * @return Number of satellites visible. If unknown, set to UINT8_MAX - */ -static inline uint8_t mavlink_msg_hil_gps_get_satellites_visible(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 35); -} - -/** - * @brief Get field id from hil_gps message - * - * @return GPS ID (zero indexed). Used for multiple GPS inputs - */ -static inline uint8_t mavlink_msg_hil_gps_get_id(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 36); -} - -/** - * @brief Get field yaw from hil_gps message - * - * @return [cdeg] Yaw of vehicle relative to Earth's North, zero means not available, use 36000 for north - */ -static inline uint16_t mavlink_msg_hil_gps_get_yaw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 37); -} - -/** - * @brief Decode a hil_gps message into a struct - * - * @param msg The message to decode - * @param hil_gps C-struct to decode the message contents into - */ -static inline void mavlink_msg_hil_gps_decode(const mavlink_message_t* msg, mavlink_hil_gps_t* hil_gps) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - hil_gps->time_usec = mavlink_msg_hil_gps_get_time_usec(msg); - hil_gps->lat = mavlink_msg_hil_gps_get_lat(msg); - hil_gps->lon = mavlink_msg_hil_gps_get_lon(msg); - hil_gps->alt = mavlink_msg_hil_gps_get_alt(msg); - hil_gps->eph = mavlink_msg_hil_gps_get_eph(msg); - hil_gps->epv = mavlink_msg_hil_gps_get_epv(msg); - hil_gps->vel = mavlink_msg_hil_gps_get_vel(msg); - hil_gps->vn = mavlink_msg_hil_gps_get_vn(msg); - hil_gps->ve = mavlink_msg_hil_gps_get_ve(msg); - hil_gps->vd = mavlink_msg_hil_gps_get_vd(msg); - hil_gps->cog = mavlink_msg_hil_gps_get_cog(msg); - hil_gps->fix_type = mavlink_msg_hil_gps_get_fix_type(msg); - hil_gps->satellites_visible = mavlink_msg_hil_gps_get_satellites_visible(msg); - hil_gps->id = mavlink_msg_hil_gps_get_id(msg); - hil_gps->yaw = mavlink_msg_hil_gps_get_yaw(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_HIL_GPS_LEN? msg->len : MAVLINK_MSG_ID_HIL_GPS_LEN; - memset(hil_gps, 0, MAVLINK_MSG_ID_HIL_GPS_LEN); - memcpy(hil_gps, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_hil_optical_flow.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_hil_optical_flow.h deleted file mode 100644 index de0ec247..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_hil_optical_flow.h +++ /dev/null @@ -1,488 +0,0 @@ -#pragma once -// MESSAGE HIL_OPTICAL_FLOW PACKING - -#define MAVLINK_MSG_ID_HIL_OPTICAL_FLOW 114 - - -typedef struct __mavlink_hil_optical_flow_t { - uint64_t time_usec; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/ - uint32_t integration_time_us; /*< [us] Integration time. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the.*/ - float integrated_x; /*< [rad] Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.)*/ - float integrated_y; /*< [rad] Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.)*/ - float integrated_xgyro; /*< [rad] RH rotation around X axis*/ - float integrated_ygyro; /*< [rad] RH rotation around Y axis*/ - float integrated_zgyro; /*< [rad] RH rotation around Z axis*/ - uint32_t time_delta_distance_us; /*< [us] Time since the distance was sampled.*/ - float distance; /*< [m] Distance to the center of the flow field. Positive value (including zero): distance known. Negative value: Unknown distance.*/ - int16_t temperature; /*< [cdegC] Temperature*/ - uint8_t sensor_id; /*< Sensor ID*/ - uint8_t quality; /*< Optical flow quality / confidence. 0: no valid flow, 255: maximum quality*/ -} mavlink_hil_optical_flow_t; - -#define MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN 44 -#define MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_MIN_LEN 44 -#define MAVLINK_MSG_ID_114_LEN 44 -#define MAVLINK_MSG_ID_114_MIN_LEN 44 - -#define MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_CRC 237 -#define MAVLINK_MSG_ID_114_CRC 237 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_HIL_OPTICAL_FLOW { \ - 114, \ - "HIL_OPTICAL_FLOW", \ - 12, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_optical_flow_t, time_usec) }, \ - { "sensor_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 42, offsetof(mavlink_hil_optical_flow_t, sensor_id) }, \ - { "integration_time_us", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_hil_optical_flow_t, integration_time_us) }, \ - { "integrated_x", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_hil_optical_flow_t, integrated_x) }, \ - { "integrated_y", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_hil_optical_flow_t, integrated_y) }, \ - { "integrated_xgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_hil_optical_flow_t, integrated_xgyro) }, \ - { "integrated_ygyro", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_hil_optical_flow_t, integrated_ygyro) }, \ - { "integrated_zgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_hil_optical_flow_t, integrated_zgyro) }, \ - { "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 40, offsetof(mavlink_hil_optical_flow_t, temperature) }, \ - { "quality", NULL, MAVLINK_TYPE_UINT8_T, 0, 43, offsetof(mavlink_hil_optical_flow_t, quality) }, \ - { "time_delta_distance_us", NULL, MAVLINK_TYPE_UINT32_T, 0, 32, offsetof(mavlink_hil_optical_flow_t, time_delta_distance_us) }, \ - { "distance", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_hil_optical_flow_t, distance) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_HIL_OPTICAL_FLOW { \ - "HIL_OPTICAL_FLOW", \ - 12, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_optical_flow_t, time_usec) }, \ - { "sensor_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 42, offsetof(mavlink_hil_optical_flow_t, sensor_id) }, \ - { "integration_time_us", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_hil_optical_flow_t, integration_time_us) }, \ - { "integrated_x", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_hil_optical_flow_t, integrated_x) }, \ - { "integrated_y", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_hil_optical_flow_t, integrated_y) }, \ - { "integrated_xgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_hil_optical_flow_t, integrated_xgyro) }, \ - { "integrated_ygyro", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_hil_optical_flow_t, integrated_ygyro) }, \ - { "integrated_zgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_hil_optical_flow_t, integrated_zgyro) }, \ - { "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 40, offsetof(mavlink_hil_optical_flow_t, temperature) }, \ - { "quality", NULL, MAVLINK_TYPE_UINT8_T, 0, 43, offsetof(mavlink_hil_optical_flow_t, quality) }, \ - { "time_delta_distance_us", NULL, MAVLINK_TYPE_UINT32_T, 0, 32, offsetof(mavlink_hil_optical_flow_t, time_delta_distance_us) }, \ - { "distance", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_hil_optical_flow_t, distance) }, \ - } \ -} -#endif - -/** - * @brief Pack a hil_optical_flow message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @param sensor_id Sensor ID - * @param integration_time_us [us] Integration time. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the. - * @param integrated_x [rad] Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.) - * @param integrated_y [rad] Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.) - * @param integrated_xgyro [rad] RH rotation around X axis - * @param integrated_ygyro [rad] RH rotation around Y axis - * @param integrated_zgyro [rad] RH rotation around Z axis - * @param temperature [cdegC] Temperature - * @param quality Optical flow quality / confidence. 0: no valid flow, 255: maximum quality - * @param time_delta_distance_us [us] Time since the distance was sampled. - * @param distance [m] Distance to the center of the flow field. Positive value (including zero): distance known. Negative value: Unknown distance. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_hil_optical_flow_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint64_t time_usec, uint8_t sensor_id, uint32_t integration_time_us, float integrated_x, float integrated_y, float integrated_xgyro, float integrated_ygyro, float integrated_zgyro, int16_t temperature, uint8_t quality, uint32_t time_delta_distance_us, float distance) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint32_t(buf, 8, integration_time_us); - _mav_put_float(buf, 12, integrated_x); - _mav_put_float(buf, 16, integrated_y); - _mav_put_float(buf, 20, integrated_xgyro); - _mav_put_float(buf, 24, integrated_ygyro); - _mav_put_float(buf, 28, integrated_zgyro); - _mav_put_uint32_t(buf, 32, time_delta_distance_us); - _mav_put_float(buf, 36, distance); - _mav_put_int16_t(buf, 40, temperature); - _mav_put_uint8_t(buf, 42, sensor_id); - _mav_put_uint8_t(buf, 43, quality); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN); -#else - mavlink_hil_optical_flow_t packet; - packet.time_usec = time_usec; - packet.integration_time_us = integration_time_us; - packet.integrated_x = integrated_x; - packet.integrated_y = integrated_y; - packet.integrated_xgyro = integrated_xgyro; - packet.integrated_ygyro = integrated_ygyro; - packet.integrated_zgyro = integrated_zgyro; - packet.time_delta_distance_us = time_delta_distance_us; - packet.distance = distance; - packet.temperature = temperature; - packet.sensor_id = sensor_id; - packet.quality = quality; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_HIL_OPTICAL_FLOW; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_MIN_LEN, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_CRC); -} - -/** - * @brief Pack a hil_optical_flow message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @param sensor_id Sensor ID - * @param integration_time_us [us] Integration time. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the. - * @param integrated_x [rad] Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.) - * @param integrated_y [rad] Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.) - * @param integrated_xgyro [rad] RH rotation around X axis - * @param integrated_ygyro [rad] RH rotation around Y axis - * @param integrated_zgyro [rad] RH rotation around Z axis - * @param temperature [cdegC] Temperature - * @param quality Optical flow quality / confidence. 0: no valid flow, 255: maximum quality - * @param time_delta_distance_us [us] Time since the distance was sampled. - * @param distance [m] Distance to the center of the flow field. Positive value (including zero): distance known. Negative value: Unknown distance. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_hil_optical_flow_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint64_t time_usec,uint8_t sensor_id,uint32_t integration_time_us,float integrated_x,float integrated_y,float integrated_xgyro,float integrated_ygyro,float integrated_zgyro,int16_t temperature,uint8_t quality,uint32_t time_delta_distance_us,float distance) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint32_t(buf, 8, integration_time_us); - _mav_put_float(buf, 12, integrated_x); - _mav_put_float(buf, 16, integrated_y); - _mav_put_float(buf, 20, integrated_xgyro); - _mav_put_float(buf, 24, integrated_ygyro); - _mav_put_float(buf, 28, integrated_zgyro); - _mav_put_uint32_t(buf, 32, time_delta_distance_us); - _mav_put_float(buf, 36, distance); - _mav_put_int16_t(buf, 40, temperature); - _mav_put_uint8_t(buf, 42, sensor_id); - _mav_put_uint8_t(buf, 43, quality); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN); -#else - mavlink_hil_optical_flow_t packet; - packet.time_usec = time_usec; - packet.integration_time_us = integration_time_us; - packet.integrated_x = integrated_x; - packet.integrated_y = integrated_y; - packet.integrated_xgyro = integrated_xgyro; - packet.integrated_ygyro = integrated_ygyro; - packet.integrated_zgyro = integrated_zgyro; - packet.time_delta_distance_us = time_delta_distance_us; - packet.distance = distance; - packet.temperature = temperature; - packet.sensor_id = sensor_id; - packet.quality = quality; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_HIL_OPTICAL_FLOW; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_MIN_LEN, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_CRC); -} - -/** - * @brief Encode a hil_optical_flow struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param hil_optical_flow C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_hil_optical_flow_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_hil_optical_flow_t* hil_optical_flow) -{ - return mavlink_msg_hil_optical_flow_pack(system_id, component_id, msg, hil_optical_flow->time_usec, hil_optical_flow->sensor_id, hil_optical_flow->integration_time_us, hil_optical_flow->integrated_x, hil_optical_flow->integrated_y, hil_optical_flow->integrated_xgyro, hil_optical_flow->integrated_ygyro, hil_optical_flow->integrated_zgyro, hil_optical_flow->temperature, hil_optical_flow->quality, hil_optical_flow->time_delta_distance_us, hil_optical_flow->distance); -} - -/** - * @brief Encode a hil_optical_flow struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param hil_optical_flow C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_hil_optical_flow_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_hil_optical_flow_t* hil_optical_flow) -{ - return mavlink_msg_hil_optical_flow_pack_chan(system_id, component_id, chan, msg, hil_optical_flow->time_usec, hil_optical_flow->sensor_id, hil_optical_flow->integration_time_us, hil_optical_flow->integrated_x, hil_optical_flow->integrated_y, hil_optical_flow->integrated_xgyro, hil_optical_flow->integrated_ygyro, hil_optical_flow->integrated_zgyro, hil_optical_flow->temperature, hil_optical_flow->quality, hil_optical_flow->time_delta_distance_us, hil_optical_flow->distance); -} - -/** - * @brief Send a hil_optical_flow message - * @param chan MAVLink channel to send the message - * - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @param sensor_id Sensor ID - * @param integration_time_us [us] Integration time. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the. - * @param integrated_x [rad] Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.) - * @param integrated_y [rad] Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.) - * @param integrated_xgyro [rad] RH rotation around X axis - * @param integrated_ygyro [rad] RH rotation around Y axis - * @param integrated_zgyro [rad] RH rotation around Z axis - * @param temperature [cdegC] Temperature - * @param quality Optical flow quality / confidence. 0: no valid flow, 255: maximum quality - * @param time_delta_distance_us [us] Time since the distance was sampled. - * @param distance [m] Distance to the center of the flow field. Positive value (including zero): distance known. Negative value: Unknown distance. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_hil_optical_flow_send(mavlink_channel_t chan, uint64_t time_usec, uint8_t sensor_id, uint32_t integration_time_us, float integrated_x, float integrated_y, float integrated_xgyro, float integrated_ygyro, float integrated_zgyro, int16_t temperature, uint8_t quality, uint32_t time_delta_distance_us, float distance) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint32_t(buf, 8, integration_time_us); - _mav_put_float(buf, 12, integrated_x); - _mav_put_float(buf, 16, integrated_y); - _mav_put_float(buf, 20, integrated_xgyro); - _mav_put_float(buf, 24, integrated_ygyro); - _mav_put_float(buf, 28, integrated_zgyro); - _mav_put_uint32_t(buf, 32, time_delta_distance_us); - _mav_put_float(buf, 36, distance); - _mav_put_int16_t(buf, 40, temperature); - _mav_put_uint8_t(buf, 42, sensor_id); - _mav_put_uint8_t(buf, 43, quality); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW, buf, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_MIN_LEN, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_CRC); -#else - mavlink_hil_optical_flow_t packet; - packet.time_usec = time_usec; - packet.integration_time_us = integration_time_us; - packet.integrated_x = integrated_x; - packet.integrated_y = integrated_y; - packet.integrated_xgyro = integrated_xgyro; - packet.integrated_ygyro = integrated_ygyro; - packet.integrated_zgyro = integrated_zgyro; - packet.time_delta_distance_us = time_delta_distance_us; - packet.distance = distance; - packet.temperature = temperature; - packet.sensor_id = sensor_id; - packet.quality = quality; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW, (const char *)&packet, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_MIN_LEN, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_CRC); -#endif -} - -/** - * @brief Send a hil_optical_flow message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_hil_optical_flow_send_struct(mavlink_channel_t chan, const mavlink_hil_optical_flow_t* hil_optical_flow) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_hil_optical_flow_send(chan, hil_optical_flow->time_usec, hil_optical_flow->sensor_id, hil_optical_flow->integration_time_us, hil_optical_flow->integrated_x, hil_optical_flow->integrated_y, hil_optical_flow->integrated_xgyro, hil_optical_flow->integrated_ygyro, hil_optical_flow->integrated_zgyro, hil_optical_flow->temperature, hil_optical_flow->quality, hil_optical_flow->time_delta_distance_us, hil_optical_flow->distance); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW, (const char *)hil_optical_flow, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_MIN_LEN, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_CRC); -#endif -} - -#if MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_hil_optical_flow_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, uint8_t sensor_id, uint32_t integration_time_us, float integrated_x, float integrated_y, float integrated_xgyro, float integrated_ygyro, float integrated_zgyro, int16_t temperature, uint8_t quality, uint32_t time_delta_distance_us, float distance) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint32_t(buf, 8, integration_time_us); - _mav_put_float(buf, 12, integrated_x); - _mav_put_float(buf, 16, integrated_y); - _mav_put_float(buf, 20, integrated_xgyro); - _mav_put_float(buf, 24, integrated_ygyro); - _mav_put_float(buf, 28, integrated_zgyro); - _mav_put_uint32_t(buf, 32, time_delta_distance_us); - _mav_put_float(buf, 36, distance); - _mav_put_int16_t(buf, 40, temperature); - _mav_put_uint8_t(buf, 42, sensor_id); - _mav_put_uint8_t(buf, 43, quality); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW, buf, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_MIN_LEN, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_CRC); -#else - mavlink_hil_optical_flow_t *packet = (mavlink_hil_optical_flow_t *)msgbuf; - packet->time_usec = time_usec; - packet->integration_time_us = integration_time_us; - packet->integrated_x = integrated_x; - packet->integrated_y = integrated_y; - packet->integrated_xgyro = integrated_xgyro; - packet->integrated_ygyro = integrated_ygyro; - packet->integrated_zgyro = integrated_zgyro; - packet->time_delta_distance_us = time_delta_distance_us; - packet->distance = distance; - packet->temperature = temperature; - packet->sensor_id = sensor_id; - packet->quality = quality; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW, (const char *)packet, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_MIN_LEN, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_CRC); -#endif -} -#endif - -#endif - -// MESSAGE HIL_OPTICAL_FLOW UNPACKING - - -/** - * @brief Get field time_usec from hil_optical_flow message - * - * @return [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - */ -static inline uint64_t mavlink_msg_hil_optical_flow_get_time_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field sensor_id from hil_optical_flow message - * - * @return Sensor ID - */ -static inline uint8_t mavlink_msg_hil_optical_flow_get_sensor_id(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 42); -} - -/** - * @brief Get field integration_time_us from hil_optical_flow message - * - * @return [us] Integration time. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the. - */ -static inline uint32_t mavlink_msg_hil_optical_flow_get_integration_time_us(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 8); -} - -/** - * @brief Get field integrated_x from hil_optical_flow message - * - * @return [rad] Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.) - */ -static inline float mavlink_msg_hil_optical_flow_get_integrated_x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field integrated_y from hil_optical_flow message - * - * @return [rad] Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.) - */ -static inline float mavlink_msg_hil_optical_flow_get_integrated_y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field integrated_xgyro from hil_optical_flow message - * - * @return [rad] RH rotation around X axis - */ -static inline float mavlink_msg_hil_optical_flow_get_integrated_xgyro(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Get field integrated_ygyro from hil_optical_flow message - * - * @return [rad] RH rotation around Y axis - */ -static inline float mavlink_msg_hil_optical_flow_get_integrated_ygyro(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Get field integrated_zgyro from hil_optical_flow message - * - * @return [rad] RH rotation around Z axis - */ -static inline float mavlink_msg_hil_optical_flow_get_integrated_zgyro(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 28); -} - -/** - * @brief Get field temperature from hil_optical_flow message - * - * @return [cdegC] Temperature - */ -static inline int16_t mavlink_msg_hil_optical_flow_get_temperature(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 40); -} - -/** - * @brief Get field quality from hil_optical_flow message - * - * @return Optical flow quality / confidence. 0: no valid flow, 255: maximum quality - */ -static inline uint8_t mavlink_msg_hil_optical_flow_get_quality(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 43); -} - -/** - * @brief Get field time_delta_distance_us from hil_optical_flow message - * - * @return [us] Time since the distance was sampled. - */ -static inline uint32_t mavlink_msg_hil_optical_flow_get_time_delta_distance_us(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 32); -} - -/** - * @brief Get field distance from hil_optical_flow message - * - * @return [m] Distance to the center of the flow field. Positive value (including zero): distance known. Negative value: Unknown distance. - */ -static inline float mavlink_msg_hil_optical_flow_get_distance(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 36); -} - -/** - * @brief Decode a hil_optical_flow message into a struct - * - * @param msg The message to decode - * @param hil_optical_flow C-struct to decode the message contents into - */ -static inline void mavlink_msg_hil_optical_flow_decode(const mavlink_message_t* msg, mavlink_hil_optical_flow_t* hil_optical_flow) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - hil_optical_flow->time_usec = mavlink_msg_hil_optical_flow_get_time_usec(msg); - hil_optical_flow->integration_time_us = mavlink_msg_hil_optical_flow_get_integration_time_us(msg); - hil_optical_flow->integrated_x = mavlink_msg_hil_optical_flow_get_integrated_x(msg); - hil_optical_flow->integrated_y = mavlink_msg_hil_optical_flow_get_integrated_y(msg); - hil_optical_flow->integrated_xgyro = mavlink_msg_hil_optical_flow_get_integrated_xgyro(msg); - hil_optical_flow->integrated_ygyro = mavlink_msg_hil_optical_flow_get_integrated_ygyro(msg); - hil_optical_flow->integrated_zgyro = mavlink_msg_hil_optical_flow_get_integrated_zgyro(msg); - hil_optical_flow->time_delta_distance_us = mavlink_msg_hil_optical_flow_get_time_delta_distance_us(msg); - hil_optical_flow->distance = mavlink_msg_hil_optical_flow_get_distance(msg); - hil_optical_flow->temperature = mavlink_msg_hil_optical_flow_get_temperature(msg); - hil_optical_flow->sensor_id = mavlink_msg_hil_optical_flow_get_sensor_id(msg); - hil_optical_flow->quality = mavlink_msg_hil_optical_flow_get_quality(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN? msg->len : MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN; - memset(hil_optical_flow, 0, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN); - memcpy(hil_optical_flow, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_hil_rc_inputs_raw.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_hil_rc_inputs_raw.h deleted file mode 100644 index 78cad3fd..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_hil_rc_inputs_raw.h +++ /dev/null @@ -1,538 +0,0 @@ -#pragma once -// MESSAGE HIL_RC_INPUTS_RAW PACKING - -#define MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW 92 - - -typedef struct __mavlink_hil_rc_inputs_raw_t { - uint64_t time_usec; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/ - uint16_t chan1_raw; /*< [us] RC channel 1 value*/ - uint16_t chan2_raw; /*< [us] RC channel 2 value*/ - uint16_t chan3_raw; /*< [us] RC channel 3 value*/ - uint16_t chan4_raw; /*< [us] RC channel 4 value*/ - uint16_t chan5_raw; /*< [us] RC channel 5 value*/ - uint16_t chan6_raw; /*< [us] RC channel 6 value*/ - uint16_t chan7_raw; /*< [us] RC channel 7 value*/ - uint16_t chan8_raw; /*< [us] RC channel 8 value*/ - uint16_t chan9_raw; /*< [us] RC channel 9 value*/ - uint16_t chan10_raw; /*< [us] RC channel 10 value*/ - uint16_t chan11_raw; /*< [us] RC channel 11 value*/ - uint16_t chan12_raw; /*< [us] RC channel 12 value*/ - uint8_t rssi; /*< Receive signal strength indicator in device-dependent units/scale. Values: [0-254], UINT8_MAX: invalid/unknown.*/ -} mavlink_hil_rc_inputs_raw_t; - -#define MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN 33 -#define MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_MIN_LEN 33 -#define MAVLINK_MSG_ID_92_LEN 33 -#define MAVLINK_MSG_ID_92_MIN_LEN 33 - -#define MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_CRC 54 -#define MAVLINK_MSG_ID_92_CRC 54 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_HIL_RC_INPUTS_RAW { \ - 92, \ - "HIL_RC_INPUTS_RAW", \ - 14, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_rc_inputs_raw_t, time_usec) }, \ - { "chan1_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_hil_rc_inputs_raw_t, chan1_raw) }, \ - { "chan2_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_hil_rc_inputs_raw_t, chan2_raw) }, \ - { "chan3_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_hil_rc_inputs_raw_t, chan3_raw) }, \ - { "chan4_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_hil_rc_inputs_raw_t, chan4_raw) }, \ - { "chan5_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_hil_rc_inputs_raw_t, chan5_raw) }, \ - { "chan6_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_hil_rc_inputs_raw_t, chan6_raw) }, \ - { "chan7_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_hil_rc_inputs_raw_t, chan7_raw) }, \ - { "chan8_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_hil_rc_inputs_raw_t, chan8_raw) }, \ - { "chan9_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_hil_rc_inputs_raw_t, chan9_raw) }, \ - { "chan10_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_hil_rc_inputs_raw_t, chan10_raw) }, \ - { "chan11_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_hil_rc_inputs_raw_t, chan11_raw) }, \ - { "chan12_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 30, offsetof(mavlink_hil_rc_inputs_raw_t, chan12_raw) }, \ - { "rssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_hil_rc_inputs_raw_t, rssi) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_HIL_RC_INPUTS_RAW { \ - "HIL_RC_INPUTS_RAW", \ - 14, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_rc_inputs_raw_t, time_usec) }, \ - { "chan1_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_hil_rc_inputs_raw_t, chan1_raw) }, \ - { "chan2_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_hil_rc_inputs_raw_t, chan2_raw) }, \ - { "chan3_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_hil_rc_inputs_raw_t, chan3_raw) }, \ - { "chan4_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_hil_rc_inputs_raw_t, chan4_raw) }, \ - { "chan5_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_hil_rc_inputs_raw_t, chan5_raw) }, \ - { "chan6_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_hil_rc_inputs_raw_t, chan6_raw) }, \ - { "chan7_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_hil_rc_inputs_raw_t, chan7_raw) }, \ - { "chan8_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_hil_rc_inputs_raw_t, chan8_raw) }, \ - { "chan9_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_hil_rc_inputs_raw_t, chan9_raw) }, \ - { "chan10_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_hil_rc_inputs_raw_t, chan10_raw) }, \ - { "chan11_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_hil_rc_inputs_raw_t, chan11_raw) }, \ - { "chan12_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 30, offsetof(mavlink_hil_rc_inputs_raw_t, chan12_raw) }, \ - { "rssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_hil_rc_inputs_raw_t, rssi) }, \ - } \ -} -#endif - -/** - * @brief Pack a hil_rc_inputs_raw message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @param chan1_raw [us] RC channel 1 value - * @param chan2_raw [us] RC channel 2 value - * @param chan3_raw [us] RC channel 3 value - * @param chan4_raw [us] RC channel 4 value - * @param chan5_raw [us] RC channel 5 value - * @param chan6_raw [us] RC channel 6 value - * @param chan7_raw [us] RC channel 7 value - * @param chan8_raw [us] RC channel 8 value - * @param chan9_raw [us] RC channel 9 value - * @param chan10_raw [us] RC channel 10 value - * @param chan11_raw [us] RC channel 11 value - * @param chan12_raw [us] RC channel 12 value - * @param rssi Receive signal strength indicator in device-dependent units/scale. Values: [0-254], UINT8_MAX: invalid/unknown. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_hil_rc_inputs_raw_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint64_t time_usec, uint16_t chan1_raw, uint16_t chan2_raw, uint16_t chan3_raw, uint16_t chan4_raw, uint16_t chan5_raw, uint16_t chan6_raw, uint16_t chan7_raw, uint16_t chan8_raw, uint16_t chan9_raw, uint16_t chan10_raw, uint16_t chan11_raw, uint16_t chan12_raw, uint8_t rssi) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint16_t(buf, 8, chan1_raw); - _mav_put_uint16_t(buf, 10, chan2_raw); - _mav_put_uint16_t(buf, 12, chan3_raw); - _mav_put_uint16_t(buf, 14, chan4_raw); - _mav_put_uint16_t(buf, 16, chan5_raw); - _mav_put_uint16_t(buf, 18, chan6_raw); - _mav_put_uint16_t(buf, 20, chan7_raw); - _mav_put_uint16_t(buf, 22, chan8_raw); - _mav_put_uint16_t(buf, 24, chan9_raw); - _mav_put_uint16_t(buf, 26, chan10_raw); - _mav_put_uint16_t(buf, 28, chan11_raw); - _mav_put_uint16_t(buf, 30, chan12_raw); - _mav_put_uint8_t(buf, 32, rssi); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN); -#else - mavlink_hil_rc_inputs_raw_t packet; - packet.time_usec = time_usec; - packet.chan1_raw = chan1_raw; - packet.chan2_raw = chan2_raw; - packet.chan3_raw = chan3_raw; - packet.chan4_raw = chan4_raw; - packet.chan5_raw = chan5_raw; - packet.chan6_raw = chan6_raw; - packet.chan7_raw = chan7_raw; - packet.chan8_raw = chan8_raw; - packet.chan9_raw = chan9_raw; - packet.chan10_raw = chan10_raw; - packet.chan11_raw = chan11_raw; - packet.chan12_raw = chan12_raw; - packet.rssi = rssi; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_MIN_LEN, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_CRC); -} - -/** - * @brief Pack a hil_rc_inputs_raw message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @param chan1_raw [us] RC channel 1 value - * @param chan2_raw [us] RC channel 2 value - * @param chan3_raw [us] RC channel 3 value - * @param chan4_raw [us] RC channel 4 value - * @param chan5_raw [us] RC channel 5 value - * @param chan6_raw [us] RC channel 6 value - * @param chan7_raw [us] RC channel 7 value - * @param chan8_raw [us] RC channel 8 value - * @param chan9_raw [us] RC channel 9 value - * @param chan10_raw [us] RC channel 10 value - * @param chan11_raw [us] RC channel 11 value - * @param chan12_raw [us] RC channel 12 value - * @param rssi Receive signal strength indicator in device-dependent units/scale. Values: [0-254], UINT8_MAX: invalid/unknown. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_hil_rc_inputs_raw_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint64_t time_usec,uint16_t chan1_raw,uint16_t chan2_raw,uint16_t chan3_raw,uint16_t chan4_raw,uint16_t chan5_raw,uint16_t chan6_raw,uint16_t chan7_raw,uint16_t chan8_raw,uint16_t chan9_raw,uint16_t chan10_raw,uint16_t chan11_raw,uint16_t chan12_raw,uint8_t rssi) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint16_t(buf, 8, chan1_raw); - _mav_put_uint16_t(buf, 10, chan2_raw); - _mav_put_uint16_t(buf, 12, chan3_raw); - _mav_put_uint16_t(buf, 14, chan4_raw); - _mav_put_uint16_t(buf, 16, chan5_raw); - _mav_put_uint16_t(buf, 18, chan6_raw); - _mav_put_uint16_t(buf, 20, chan7_raw); - _mav_put_uint16_t(buf, 22, chan8_raw); - _mav_put_uint16_t(buf, 24, chan9_raw); - _mav_put_uint16_t(buf, 26, chan10_raw); - _mav_put_uint16_t(buf, 28, chan11_raw); - _mav_put_uint16_t(buf, 30, chan12_raw); - _mav_put_uint8_t(buf, 32, rssi); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN); -#else - mavlink_hil_rc_inputs_raw_t packet; - packet.time_usec = time_usec; - packet.chan1_raw = chan1_raw; - packet.chan2_raw = chan2_raw; - packet.chan3_raw = chan3_raw; - packet.chan4_raw = chan4_raw; - packet.chan5_raw = chan5_raw; - packet.chan6_raw = chan6_raw; - packet.chan7_raw = chan7_raw; - packet.chan8_raw = chan8_raw; - packet.chan9_raw = chan9_raw; - packet.chan10_raw = chan10_raw; - packet.chan11_raw = chan11_raw; - packet.chan12_raw = chan12_raw; - packet.rssi = rssi; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_MIN_LEN, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_CRC); -} - -/** - * @brief Encode a hil_rc_inputs_raw struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param hil_rc_inputs_raw C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_hil_rc_inputs_raw_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_hil_rc_inputs_raw_t* hil_rc_inputs_raw) -{ - return mavlink_msg_hil_rc_inputs_raw_pack(system_id, component_id, msg, hil_rc_inputs_raw->time_usec, hil_rc_inputs_raw->chan1_raw, hil_rc_inputs_raw->chan2_raw, hil_rc_inputs_raw->chan3_raw, hil_rc_inputs_raw->chan4_raw, hil_rc_inputs_raw->chan5_raw, hil_rc_inputs_raw->chan6_raw, hil_rc_inputs_raw->chan7_raw, hil_rc_inputs_raw->chan8_raw, hil_rc_inputs_raw->chan9_raw, hil_rc_inputs_raw->chan10_raw, hil_rc_inputs_raw->chan11_raw, hil_rc_inputs_raw->chan12_raw, hil_rc_inputs_raw->rssi); -} - -/** - * @brief Encode a hil_rc_inputs_raw struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param hil_rc_inputs_raw C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_hil_rc_inputs_raw_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_hil_rc_inputs_raw_t* hil_rc_inputs_raw) -{ - return mavlink_msg_hil_rc_inputs_raw_pack_chan(system_id, component_id, chan, msg, hil_rc_inputs_raw->time_usec, hil_rc_inputs_raw->chan1_raw, hil_rc_inputs_raw->chan2_raw, hil_rc_inputs_raw->chan3_raw, hil_rc_inputs_raw->chan4_raw, hil_rc_inputs_raw->chan5_raw, hil_rc_inputs_raw->chan6_raw, hil_rc_inputs_raw->chan7_raw, hil_rc_inputs_raw->chan8_raw, hil_rc_inputs_raw->chan9_raw, hil_rc_inputs_raw->chan10_raw, hil_rc_inputs_raw->chan11_raw, hil_rc_inputs_raw->chan12_raw, hil_rc_inputs_raw->rssi); -} - -/** - * @brief Send a hil_rc_inputs_raw message - * @param chan MAVLink channel to send the message - * - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @param chan1_raw [us] RC channel 1 value - * @param chan2_raw [us] RC channel 2 value - * @param chan3_raw [us] RC channel 3 value - * @param chan4_raw [us] RC channel 4 value - * @param chan5_raw [us] RC channel 5 value - * @param chan6_raw [us] RC channel 6 value - * @param chan7_raw [us] RC channel 7 value - * @param chan8_raw [us] RC channel 8 value - * @param chan9_raw [us] RC channel 9 value - * @param chan10_raw [us] RC channel 10 value - * @param chan11_raw [us] RC channel 11 value - * @param chan12_raw [us] RC channel 12 value - * @param rssi Receive signal strength indicator in device-dependent units/scale. Values: [0-254], UINT8_MAX: invalid/unknown. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_hil_rc_inputs_raw_send(mavlink_channel_t chan, uint64_t time_usec, uint16_t chan1_raw, uint16_t chan2_raw, uint16_t chan3_raw, uint16_t chan4_raw, uint16_t chan5_raw, uint16_t chan6_raw, uint16_t chan7_raw, uint16_t chan8_raw, uint16_t chan9_raw, uint16_t chan10_raw, uint16_t chan11_raw, uint16_t chan12_raw, uint8_t rssi) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint16_t(buf, 8, chan1_raw); - _mav_put_uint16_t(buf, 10, chan2_raw); - _mav_put_uint16_t(buf, 12, chan3_raw); - _mav_put_uint16_t(buf, 14, chan4_raw); - _mav_put_uint16_t(buf, 16, chan5_raw); - _mav_put_uint16_t(buf, 18, chan6_raw); - _mav_put_uint16_t(buf, 20, chan7_raw); - _mav_put_uint16_t(buf, 22, chan8_raw); - _mav_put_uint16_t(buf, 24, chan9_raw); - _mav_put_uint16_t(buf, 26, chan10_raw); - _mav_put_uint16_t(buf, 28, chan11_raw); - _mav_put_uint16_t(buf, 30, chan12_raw); - _mav_put_uint8_t(buf, 32, rssi); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW, buf, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_MIN_LEN, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_CRC); -#else - mavlink_hil_rc_inputs_raw_t packet; - packet.time_usec = time_usec; - packet.chan1_raw = chan1_raw; - packet.chan2_raw = chan2_raw; - packet.chan3_raw = chan3_raw; - packet.chan4_raw = chan4_raw; - packet.chan5_raw = chan5_raw; - packet.chan6_raw = chan6_raw; - packet.chan7_raw = chan7_raw; - packet.chan8_raw = chan8_raw; - packet.chan9_raw = chan9_raw; - packet.chan10_raw = chan10_raw; - packet.chan11_raw = chan11_raw; - packet.chan12_raw = chan12_raw; - packet.rssi = rssi; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW, (const char *)&packet, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_MIN_LEN, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_CRC); -#endif -} - -/** - * @brief Send a hil_rc_inputs_raw message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_hil_rc_inputs_raw_send_struct(mavlink_channel_t chan, const mavlink_hil_rc_inputs_raw_t* hil_rc_inputs_raw) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_hil_rc_inputs_raw_send(chan, hil_rc_inputs_raw->time_usec, hil_rc_inputs_raw->chan1_raw, hil_rc_inputs_raw->chan2_raw, hil_rc_inputs_raw->chan3_raw, hil_rc_inputs_raw->chan4_raw, hil_rc_inputs_raw->chan5_raw, hil_rc_inputs_raw->chan6_raw, hil_rc_inputs_raw->chan7_raw, hil_rc_inputs_raw->chan8_raw, hil_rc_inputs_raw->chan9_raw, hil_rc_inputs_raw->chan10_raw, hil_rc_inputs_raw->chan11_raw, hil_rc_inputs_raw->chan12_raw, hil_rc_inputs_raw->rssi); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW, (const char *)hil_rc_inputs_raw, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_MIN_LEN, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_CRC); -#endif -} - -#if MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_hil_rc_inputs_raw_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, uint16_t chan1_raw, uint16_t chan2_raw, uint16_t chan3_raw, uint16_t chan4_raw, uint16_t chan5_raw, uint16_t chan6_raw, uint16_t chan7_raw, uint16_t chan8_raw, uint16_t chan9_raw, uint16_t chan10_raw, uint16_t chan11_raw, uint16_t chan12_raw, uint8_t rssi) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint16_t(buf, 8, chan1_raw); - _mav_put_uint16_t(buf, 10, chan2_raw); - _mav_put_uint16_t(buf, 12, chan3_raw); - _mav_put_uint16_t(buf, 14, chan4_raw); - _mav_put_uint16_t(buf, 16, chan5_raw); - _mav_put_uint16_t(buf, 18, chan6_raw); - _mav_put_uint16_t(buf, 20, chan7_raw); - _mav_put_uint16_t(buf, 22, chan8_raw); - _mav_put_uint16_t(buf, 24, chan9_raw); - _mav_put_uint16_t(buf, 26, chan10_raw); - _mav_put_uint16_t(buf, 28, chan11_raw); - _mav_put_uint16_t(buf, 30, chan12_raw); - _mav_put_uint8_t(buf, 32, rssi); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW, buf, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_MIN_LEN, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_CRC); -#else - mavlink_hil_rc_inputs_raw_t *packet = (mavlink_hil_rc_inputs_raw_t *)msgbuf; - packet->time_usec = time_usec; - packet->chan1_raw = chan1_raw; - packet->chan2_raw = chan2_raw; - packet->chan3_raw = chan3_raw; - packet->chan4_raw = chan4_raw; - packet->chan5_raw = chan5_raw; - packet->chan6_raw = chan6_raw; - packet->chan7_raw = chan7_raw; - packet->chan8_raw = chan8_raw; - packet->chan9_raw = chan9_raw; - packet->chan10_raw = chan10_raw; - packet->chan11_raw = chan11_raw; - packet->chan12_raw = chan12_raw; - packet->rssi = rssi; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW, (const char *)packet, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_MIN_LEN, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_CRC); -#endif -} -#endif - -#endif - -// MESSAGE HIL_RC_INPUTS_RAW UNPACKING - - -/** - * @brief Get field time_usec from hil_rc_inputs_raw message - * - * @return [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - */ -static inline uint64_t mavlink_msg_hil_rc_inputs_raw_get_time_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field chan1_raw from hil_rc_inputs_raw message - * - * @return [us] RC channel 1 value - */ -static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan1_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 8); -} - -/** - * @brief Get field chan2_raw from hil_rc_inputs_raw message - * - * @return [us] RC channel 2 value - */ -static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan2_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 10); -} - -/** - * @brief Get field chan3_raw from hil_rc_inputs_raw message - * - * @return [us] RC channel 3 value - */ -static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan3_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 12); -} - -/** - * @brief Get field chan4_raw from hil_rc_inputs_raw message - * - * @return [us] RC channel 4 value - */ -static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan4_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 14); -} - -/** - * @brief Get field chan5_raw from hil_rc_inputs_raw message - * - * @return [us] RC channel 5 value - */ -static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan5_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 16); -} - -/** - * @brief Get field chan6_raw from hil_rc_inputs_raw message - * - * @return [us] RC channel 6 value - */ -static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan6_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 18); -} - -/** - * @brief Get field chan7_raw from hil_rc_inputs_raw message - * - * @return [us] RC channel 7 value - */ -static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan7_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 20); -} - -/** - * @brief Get field chan8_raw from hil_rc_inputs_raw message - * - * @return [us] RC channel 8 value - */ -static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan8_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 22); -} - -/** - * @brief Get field chan9_raw from hil_rc_inputs_raw message - * - * @return [us] RC channel 9 value - */ -static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan9_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 24); -} - -/** - * @brief Get field chan10_raw from hil_rc_inputs_raw message - * - * @return [us] RC channel 10 value - */ -static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan10_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 26); -} - -/** - * @brief Get field chan11_raw from hil_rc_inputs_raw message - * - * @return [us] RC channel 11 value - */ -static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan11_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 28); -} - -/** - * @brief Get field chan12_raw from hil_rc_inputs_raw message - * - * @return [us] RC channel 12 value - */ -static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan12_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 30); -} - -/** - * @brief Get field rssi from hil_rc_inputs_raw message - * - * @return Receive signal strength indicator in device-dependent units/scale. Values: [0-254], UINT8_MAX: invalid/unknown. - */ -static inline uint8_t mavlink_msg_hil_rc_inputs_raw_get_rssi(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 32); -} - -/** - * @brief Decode a hil_rc_inputs_raw message into a struct - * - * @param msg The message to decode - * @param hil_rc_inputs_raw C-struct to decode the message contents into - */ -static inline void mavlink_msg_hil_rc_inputs_raw_decode(const mavlink_message_t* msg, mavlink_hil_rc_inputs_raw_t* hil_rc_inputs_raw) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - hil_rc_inputs_raw->time_usec = mavlink_msg_hil_rc_inputs_raw_get_time_usec(msg); - hil_rc_inputs_raw->chan1_raw = mavlink_msg_hil_rc_inputs_raw_get_chan1_raw(msg); - hil_rc_inputs_raw->chan2_raw = mavlink_msg_hil_rc_inputs_raw_get_chan2_raw(msg); - hil_rc_inputs_raw->chan3_raw = mavlink_msg_hil_rc_inputs_raw_get_chan3_raw(msg); - hil_rc_inputs_raw->chan4_raw = mavlink_msg_hil_rc_inputs_raw_get_chan4_raw(msg); - hil_rc_inputs_raw->chan5_raw = mavlink_msg_hil_rc_inputs_raw_get_chan5_raw(msg); - hil_rc_inputs_raw->chan6_raw = mavlink_msg_hil_rc_inputs_raw_get_chan6_raw(msg); - hil_rc_inputs_raw->chan7_raw = mavlink_msg_hil_rc_inputs_raw_get_chan7_raw(msg); - hil_rc_inputs_raw->chan8_raw = mavlink_msg_hil_rc_inputs_raw_get_chan8_raw(msg); - hil_rc_inputs_raw->chan9_raw = mavlink_msg_hil_rc_inputs_raw_get_chan9_raw(msg); - hil_rc_inputs_raw->chan10_raw = mavlink_msg_hil_rc_inputs_raw_get_chan10_raw(msg); - hil_rc_inputs_raw->chan11_raw = mavlink_msg_hil_rc_inputs_raw_get_chan11_raw(msg); - hil_rc_inputs_raw->chan12_raw = mavlink_msg_hil_rc_inputs_raw_get_chan12_raw(msg); - hil_rc_inputs_raw->rssi = mavlink_msg_hil_rc_inputs_raw_get_rssi(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN? msg->len : MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN; - memset(hil_rc_inputs_raw, 0, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN); - memcpy(hil_rc_inputs_raw, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_hil_sensor.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_hil_sensor.h deleted file mode 100644 index 28c10c7e..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_hil_sensor.h +++ /dev/null @@ -1,588 +0,0 @@ -#pragma once -// MESSAGE HIL_SENSOR PACKING - -#define MAVLINK_MSG_ID_HIL_SENSOR 107 - - -typedef struct __mavlink_hil_sensor_t { - uint64_t time_usec; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/ - float xacc; /*< [m/s/s] X acceleration*/ - float yacc; /*< [m/s/s] Y acceleration*/ - float zacc; /*< [m/s/s] Z acceleration*/ - float xgyro; /*< [rad/s] Angular speed around X axis in body frame*/ - float ygyro; /*< [rad/s] Angular speed around Y axis in body frame*/ - float zgyro; /*< [rad/s] Angular speed around Z axis in body frame*/ - float xmag; /*< [gauss] X Magnetic field*/ - float ymag; /*< [gauss] Y Magnetic field*/ - float zmag; /*< [gauss] Z Magnetic field*/ - float abs_pressure; /*< [hPa] Absolute pressure*/ - float diff_pressure; /*< [hPa] Differential pressure (airspeed)*/ - float pressure_alt; /*< Altitude calculated from pressure*/ - float temperature; /*< [degC] Temperature*/ - uint32_t fields_updated; /*< Bitmap for fields that have updated since last message*/ - uint8_t id; /*< Sensor ID (zero indexed). Used for multiple sensor inputs*/ -} mavlink_hil_sensor_t; - -#define MAVLINK_MSG_ID_HIL_SENSOR_LEN 65 -#define MAVLINK_MSG_ID_HIL_SENSOR_MIN_LEN 64 -#define MAVLINK_MSG_ID_107_LEN 65 -#define MAVLINK_MSG_ID_107_MIN_LEN 64 - -#define MAVLINK_MSG_ID_HIL_SENSOR_CRC 108 -#define MAVLINK_MSG_ID_107_CRC 108 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_HIL_SENSOR { \ - 107, \ - "HIL_SENSOR", \ - 16, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_sensor_t, time_usec) }, \ - { "xacc", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_hil_sensor_t, xacc) }, \ - { "yacc", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_hil_sensor_t, yacc) }, \ - { "zacc", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_hil_sensor_t, zacc) }, \ - { "xgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_hil_sensor_t, xgyro) }, \ - { "ygyro", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_hil_sensor_t, ygyro) }, \ - { "zgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_hil_sensor_t, zgyro) }, \ - { "xmag", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_hil_sensor_t, xmag) }, \ - { "ymag", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_hil_sensor_t, ymag) }, \ - { "zmag", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_hil_sensor_t, zmag) }, \ - { "abs_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_hil_sensor_t, abs_pressure) }, \ - { "diff_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_hil_sensor_t, diff_pressure) }, \ - { "pressure_alt", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_hil_sensor_t, pressure_alt) }, \ - { "temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_hil_sensor_t, temperature) }, \ - { "fields_updated", NULL, MAVLINK_TYPE_UINT32_T, 0, 60, offsetof(mavlink_hil_sensor_t, fields_updated) }, \ - { "id", NULL, MAVLINK_TYPE_UINT8_T, 0, 64, offsetof(mavlink_hil_sensor_t, id) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_HIL_SENSOR { \ - "HIL_SENSOR", \ - 16, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_sensor_t, time_usec) }, \ - { "xacc", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_hil_sensor_t, xacc) }, \ - { "yacc", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_hil_sensor_t, yacc) }, \ - { "zacc", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_hil_sensor_t, zacc) }, \ - { "xgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_hil_sensor_t, xgyro) }, \ - { "ygyro", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_hil_sensor_t, ygyro) }, \ - { "zgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_hil_sensor_t, zgyro) }, \ - { "xmag", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_hil_sensor_t, xmag) }, \ - { "ymag", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_hil_sensor_t, ymag) }, \ - { "zmag", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_hil_sensor_t, zmag) }, \ - { "abs_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_hil_sensor_t, abs_pressure) }, \ - { "diff_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_hil_sensor_t, diff_pressure) }, \ - { "pressure_alt", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_hil_sensor_t, pressure_alt) }, \ - { "temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_hil_sensor_t, temperature) }, \ - { "fields_updated", NULL, MAVLINK_TYPE_UINT32_T, 0, 60, offsetof(mavlink_hil_sensor_t, fields_updated) }, \ - { "id", NULL, MAVLINK_TYPE_UINT8_T, 0, 64, offsetof(mavlink_hil_sensor_t, id) }, \ - } \ -} -#endif - -/** - * @brief Pack a hil_sensor message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @param xacc [m/s/s] X acceleration - * @param yacc [m/s/s] Y acceleration - * @param zacc [m/s/s] Z acceleration - * @param xgyro [rad/s] Angular speed around X axis in body frame - * @param ygyro [rad/s] Angular speed around Y axis in body frame - * @param zgyro [rad/s] Angular speed around Z axis in body frame - * @param xmag [gauss] X Magnetic field - * @param ymag [gauss] Y Magnetic field - * @param zmag [gauss] Z Magnetic field - * @param abs_pressure [hPa] Absolute pressure - * @param diff_pressure [hPa] Differential pressure (airspeed) - * @param pressure_alt Altitude calculated from pressure - * @param temperature [degC] Temperature - * @param fields_updated Bitmap for fields that have updated since last message - * @param id Sensor ID (zero indexed). Used for multiple sensor inputs - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_hil_sensor_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint64_t time_usec, float xacc, float yacc, float zacc, float xgyro, float ygyro, float zgyro, float xmag, float ymag, float zmag, float abs_pressure, float diff_pressure, float pressure_alt, float temperature, uint32_t fields_updated, uint8_t id) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_HIL_SENSOR_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, xacc); - _mav_put_float(buf, 12, yacc); - _mav_put_float(buf, 16, zacc); - _mav_put_float(buf, 20, xgyro); - _mav_put_float(buf, 24, ygyro); - _mav_put_float(buf, 28, zgyro); - _mav_put_float(buf, 32, xmag); - _mav_put_float(buf, 36, ymag); - _mav_put_float(buf, 40, zmag); - _mav_put_float(buf, 44, abs_pressure); - _mav_put_float(buf, 48, diff_pressure); - _mav_put_float(buf, 52, pressure_alt); - _mav_put_float(buf, 56, temperature); - _mav_put_uint32_t(buf, 60, fields_updated); - _mav_put_uint8_t(buf, 64, id); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIL_SENSOR_LEN); -#else - mavlink_hil_sensor_t packet; - packet.time_usec = time_usec; - packet.xacc = xacc; - packet.yacc = yacc; - packet.zacc = zacc; - packet.xgyro = xgyro; - packet.ygyro = ygyro; - packet.zgyro = zgyro; - packet.xmag = xmag; - packet.ymag = ymag; - packet.zmag = zmag; - packet.abs_pressure = abs_pressure; - packet.diff_pressure = diff_pressure; - packet.pressure_alt = pressure_alt; - packet.temperature = temperature; - packet.fields_updated = fields_updated; - packet.id = id; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIL_SENSOR_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_HIL_SENSOR; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HIL_SENSOR_MIN_LEN, MAVLINK_MSG_ID_HIL_SENSOR_LEN, MAVLINK_MSG_ID_HIL_SENSOR_CRC); -} - -/** - * @brief Pack a hil_sensor message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @param xacc [m/s/s] X acceleration - * @param yacc [m/s/s] Y acceleration - * @param zacc [m/s/s] Z acceleration - * @param xgyro [rad/s] Angular speed around X axis in body frame - * @param ygyro [rad/s] Angular speed around Y axis in body frame - * @param zgyro [rad/s] Angular speed around Z axis in body frame - * @param xmag [gauss] X Magnetic field - * @param ymag [gauss] Y Magnetic field - * @param zmag [gauss] Z Magnetic field - * @param abs_pressure [hPa] Absolute pressure - * @param diff_pressure [hPa] Differential pressure (airspeed) - * @param pressure_alt Altitude calculated from pressure - * @param temperature [degC] Temperature - * @param fields_updated Bitmap for fields that have updated since last message - * @param id Sensor ID (zero indexed). Used for multiple sensor inputs - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_hil_sensor_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint64_t time_usec,float xacc,float yacc,float zacc,float xgyro,float ygyro,float zgyro,float xmag,float ymag,float zmag,float abs_pressure,float diff_pressure,float pressure_alt,float temperature,uint32_t fields_updated,uint8_t id) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_HIL_SENSOR_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, xacc); - _mav_put_float(buf, 12, yacc); - _mav_put_float(buf, 16, zacc); - _mav_put_float(buf, 20, xgyro); - _mav_put_float(buf, 24, ygyro); - _mav_put_float(buf, 28, zgyro); - _mav_put_float(buf, 32, xmag); - _mav_put_float(buf, 36, ymag); - _mav_put_float(buf, 40, zmag); - _mav_put_float(buf, 44, abs_pressure); - _mav_put_float(buf, 48, diff_pressure); - _mav_put_float(buf, 52, pressure_alt); - _mav_put_float(buf, 56, temperature); - _mav_put_uint32_t(buf, 60, fields_updated); - _mav_put_uint8_t(buf, 64, id); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIL_SENSOR_LEN); -#else - mavlink_hil_sensor_t packet; - packet.time_usec = time_usec; - packet.xacc = xacc; - packet.yacc = yacc; - packet.zacc = zacc; - packet.xgyro = xgyro; - packet.ygyro = ygyro; - packet.zgyro = zgyro; - packet.xmag = xmag; - packet.ymag = ymag; - packet.zmag = zmag; - packet.abs_pressure = abs_pressure; - packet.diff_pressure = diff_pressure; - packet.pressure_alt = pressure_alt; - packet.temperature = temperature; - packet.fields_updated = fields_updated; - packet.id = id; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIL_SENSOR_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_HIL_SENSOR; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HIL_SENSOR_MIN_LEN, MAVLINK_MSG_ID_HIL_SENSOR_LEN, MAVLINK_MSG_ID_HIL_SENSOR_CRC); -} - -/** - * @brief Encode a hil_sensor struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param hil_sensor C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_hil_sensor_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_hil_sensor_t* hil_sensor) -{ - return mavlink_msg_hil_sensor_pack(system_id, component_id, msg, hil_sensor->time_usec, hil_sensor->xacc, hil_sensor->yacc, hil_sensor->zacc, hil_sensor->xgyro, hil_sensor->ygyro, hil_sensor->zgyro, hil_sensor->xmag, hil_sensor->ymag, hil_sensor->zmag, hil_sensor->abs_pressure, hil_sensor->diff_pressure, hil_sensor->pressure_alt, hil_sensor->temperature, hil_sensor->fields_updated, hil_sensor->id); -} - -/** - * @brief Encode a hil_sensor struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param hil_sensor C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_hil_sensor_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_hil_sensor_t* hil_sensor) -{ - return mavlink_msg_hil_sensor_pack_chan(system_id, component_id, chan, msg, hil_sensor->time_usec, hil_sensor->xacc, hil_sensor->yacc, hil_sensor->zacc, hil_sensor->xgyro, hil_sensor->ygyro, hil_sensor->zgyro, hil_sensor->xmag, hil_sensor->ymag, hil_sensor->zmag, hil_sensor->abs_pressure, hil_sensor->diff_pressure, hil_sensor->pressure_alt, hil_sensor->temperature, hil_sensor->fields_updated, hil_sensor->id); -} - -/** - * @brief Send a hil_sensor message - * @param chan MAVLink channel to send the message - * - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @param xacc [m/s/s] X acceleration - * @param yacc [m/s/s] Y acceleration - * @param zacc [m/s/s] Z acceleration - * @param xgyro [rad/s] Angular speed around X axis in body frame - * @param ygyro [rad/s] Angular speed around Y axis in body frame - * @param zgyro [rad/s] Angular speed around Z axis in body frame - * @param xmag [gauss] X Magnetic field - * @param ymag [gauss] Y Magnetic field - * @param zmag [gauss] Z Magnetic field - * @param abs_pressure [hPa] Absolute pressure - * @param diff_pressure [hPa] Differential pressure (airspeed) - * @param pressure_alt Altitude calculated from pressure - * @param temperature [degC] Temperature - * @param fields_updated Bitmap for fields that have updated since last message - * @param id Sensor ID (zero indexed). Used for multiple sensor inputs - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_hil_sensor_send(mavlink_channel_t chan, uint64_t time_usec, float xacc, float yacc, float zacc, float xgyro, float ygyro, float zgyro, float xmag, float ymag, float zmag, float abs_pressure, float diff_pressure, float pressure_alt, float temperature, uint32_t fields_updated, uint8_t id) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_HIL_SENSOR_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, xacc); - _mav_put_float(buf, 12, yacc); - _mav_put_float(buf, 16, zacc); - _mav_put_float(buf, 20, xgyro); - _mav_put_float(buf, 24, ygyro); - _mav_put_float(buf, 28, zgyro); - _mav_put_float(buf, 32, xmag); - _mav_put_float(buf, 36, ymag); - _mav_put_float(buf, 40, zmag); - _mav_put_float(buf, 44, abs_pressure); - _mav_put_float(buf, 48, diff_pressure); - _mav_put_float(buf, 52, pressure_alt); - _mav_put_float(buf, 56, temperature); - _mav_put_uint32_t(buf, 60, fields_updated); - _mav_put_uint8_t(buf, 64, id); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_SENSOR, buf, MAVLINK_MSG_ID_HIL_SENSOR_MIN_LEN, MAVLINK_MSG_ID_HIL_SENSOR_LEN, MAVLINK_MSG_ID_HIL_SENSOR_CRC); -#else - mavlink_hil_sensor_t packet; - packet.time_usec = time_usec; - packet.xacc = xacc; - packet.yacc = yacc; - packet.zacc = zacc; - packet.xgyro = xgyro; - packet.ygyro = ygyro; - packet.zgyro = zgyro; - packet.xmag = xmag; - packet.ymag = ymag; - packet.zmag = zmag; - packet.abs_pressure = abs_pressure; - packet.diff_pressure = diff_pressure; - packet.pressure_alt = pressure_alt; - packet.temperature = temperature; - packet.fields_updated = fields_updated; - packet.id = id; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_SENSOR, (const char *)&packet, MAVLINK_MSG_ID_HIL_SENSOR_MIN_LEN, MAVLINK_MSG_ID_HIL_SENSOR_LEN, MAVLINK_MSG_ID_HIL_SENSOR_CRC); -#endif -} - -/** - * @brief Send a hil_sensor message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_hil_sensor_send_struct(mavlink_channel_t chan, const mavlink_hil_sensor_t* hil_sensor) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_hil_sensor_send(chan, hil_sensor->time_usec, hil_sensor->xacc, hil_sensor->yacc, hil_sensor->zacc, hil_sensor->xgyro, hil_sensor->ygyro, hil_sensor->zgyro, hil_sensor->xmag, hil_sensor->ymag, hil_sensor->zmag, hil_sensor->abs_pressure, hil_sensor->diff_pressure, hil_sensor->pressure_alt, hil_sensor->temperature, hil_sensor->fields_updated, hil_sensor->id); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_SENSOR, (const char *)hil_sensor, MAVLINK_MSG_ID_HIL_SENSOR_MIN_LEN, MAVLINK_MSG_ID_HIL_SENSOR_LEN, MAVLINK_MSG_ID_HIL_SENSOR_CRC); -#endif -} - -#if MAVLINK_MSG_ID_HIL_SENSOR_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_hil_sensor_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, float xacc, float yacc, float zacc, float xgyro, float ygyro, float zgyro, float xmag, float ymag, float zmag, float abs_pressure, float diff_pressure, float pressure_alt, float temperature, uint32_t fields_updated, uint8_t id) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, xacc); - _mav_put_float(buf, 12, yacc); - _mav_put_float(buf, 16, zacc); - _mav_put_float(buf, 20, xgyro); - _mav_put_float(buf, 24, ygyro); - _mav_put_float(buf, 28, zgyro); - _mav_put_float(buf, 32, xmag); - _mav_put_float(buf, 36, ymag); - _mav_put_float(buf, 40, zmag); - _mav_put_float(buf, 44, abs_pressure); - _mav_put_float(buf, 48, diff_pressure); - _mav_put_float(buf, 52, pressure_alt); - _mav_put_float(buf, 56, temperature); - _mav_put_uint32_t(buf, 60, fields_updated); - _mav_put_uint8_t(buf, 64, id); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_SENSOR, buf, MAVLINK_MSG_ID_HIL_SENSOR_MIN_LEN, MAVLINK_MSG_ID_HIL_SENSOR_LEN, MAVLINK_MSG_ID_HIL_SENSOR_CRC); -#else - mavlink_hil_sensor_t *packet = (mavlink_hil_sensor_t *)msgbuf; - packet->time_usec = time_usec; - packet->xacc = xacc; - packet->yacc = yacc; - packet->zacc = zacc; - packet->xgyro = xgyro; - packet->ygyro = ygyro; - packet->zgyro = zgyro; - packet->xmag = xmag; - packet->ymag = ymag; - packet->zmag = zmag; - packet->abs_pressure = abs_pressure; - packet->diff_pressure = diff_pressure; - packet->pressure_alt = pressure_alt; - packet->temperature = temperature; - packet->fields_updated = fields_updated; - packet->id = id; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_SENSOR, (const char *)packet, MAVLINK_MSG_ID_HIL_SENSOR_MIN_LEN, MAVLINK_MSG_ID_HIL_SENSOR_LEN, MAVLINK_MSG_ID_HIL_SENSOR_CRC); -#endif -} -#endif - -#endif - -// MESSAGE HIL_SENSOR UNPACKING - - -/** - * @brief Get field time_usec from hil_sensor message - * - * @return [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - */ -static inline uint64_t mavlink_msg_hil_sensor_get_time_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field xacc from hil_sensor message - * - * @return [m/s/s] X acceleration - */ -static inline float mavlink_msg_hil_sensor_get_xacc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field yacc from hil_sensor message - * - * @return [m/s/s] Y acceleration - */ -static inline float mavlink_msg_hil_sensor_get_yacc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field zacc from hil_sensor message - * - * @return [m/s/s] Z acceleration - */ -static inline float mavlink_msg_hil_sensor_get_zacc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field xgyro from hil_sensor message - * - * @return [rad/s] Angular speed around X axis in body frame - */ -static inline float mavlink_msg_hil_sensor_get_xgyro(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Get field ygyro from hil_sensor message - * - * @return [rad/s] Angular speed around Y axis in body frame - */ -static inline float mavlink_msg_hil_sensor_get_ygyro(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Get field zgyro from hil_sensor message - * - * @return [rad/s] Angular speed around Z axis in body frame - */ -static inline float mavlink_msg_hil_sensor_get_zgyro(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 28); -} - -/** - * @brief Get field xmag from hil_sensor message - * - * @return [gauss] X Magnetic field - */ -static inline float mavlink_msg_hil_sensor_get_xmag(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 32); -} - -/** - * @brief Get field ymag from hil_sensor message - * - * @return [gauss] Y Magnetic field - */ -static inline float mavlink_msg_hil_sensor_get_ymag(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 36); -} - -/** - * @brief Get field zmag from hil_sensor message - * - * @return [gauss] Z Magnetic field - */ -static inline float mavlink_msg_hil_sensor_get_zmag(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 40); -} - -/** - * @brief Get field abs_pressure from hil_sensor message - * - * @return [hPa] Absolute pressure - */ -static inline float mavlink_msg_hil_sensor_get_abs_pressure(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 44); -} - -/** - * @brief Get field diff_pressure from hil_sensor message - * - * @return [hPa] Differential pressure (airspeed) - */ -static inline float mavlink_msg_hil_sensor_get_diff_pressure(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 48); -} - -/** - * @brief Get field pressure_alt from hil_sensor message - * - * @return Altitude calculated from pressure - */ -static inline float mavlink_msg_hil_sensor_get_pressure_alt(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 52); -} - -/** - * @brief Get field temperature from hil_sensor message - * - * @return [degC] Temperature - */ -static inline float mavlink_msg_hil_sensor_get_temperature(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 56); -} - -/** - * @brief Get field fields_updated from hil_sensor message - * - * @return Bitmap for fields that have updated since last message - */ -static inline uint32_t mavlink_msg_hil_sensor_get_fields_updated(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 60); -} - -/** - * @brief Get field id from hil_sensor message - * - * @return Sensor ID (zero indexed). Used for multiple sensor inputs - */ -static inline uint8_t mavlink_msg_hil_sensor_get_id(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 64); -} - -/** - * @brief Decode a hil_sensor message into a struct - * - * @param msg The message to decode - * @param hil_sensor C-struct to decode the message contents into - */ -static inline void mavlink_msg_hil_sensor_decode(const mavlink_message_t* msg, mavlink_hil_sensor_t* hil_sensor) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - hil_sensor->time_usec = mavlink_msg_hil_sensor_get_time_usec(msg); - hil_sensor->xacc = mavlink_msg_hil_sensor_get_xacc(msg); - hil_sensor->yacc = mavlink_msg_hil_sensor_get_yacc(msg); - hil_sensor->zacc = mavlink_msg_hil_sensor_get_zacc(msg); - hil_sensor->xgyro = mavlink_msg_hil_sensor_get_xgyro(msg); - hil_sensor->ygyro = mavlink_msg_hil_sensor_get_ygyro(msg); - hil_sensor->zgyro = mavlink_msg_hil_sensor_get_zgyro(msg); - hil_sensor->xmag = mavlink_msg_hil_sensor_get_xmag(msg); - hil_sensor->ymag = mavlink_msg_hil_sensor_get_ymag(msg); - hil_sensor->zmag = mavlink_msg_hil_sensor_get_zmag(msg); - hil_sensor->abs_pressure = mavlink_msg_hil_sensor_get_abs_pressure(msg); - hil_sensor->diff_pressure = mavlink_msg_hil_sensor_get_diff_pressure(msg); - hil_sensor->pressure_alt = mavlink_msg_hil_sensor_get_pressure_alt(msg); - hil_sensor->temperature = mavlink_msg_hil_sensor_get_temperature(msg); - hil_sensor->fields_updated = mavlink_msg_hil_sensor_get_fields_updated(msg); - hil_sensor->id = mavlink_msg_hil_sensor_get_id(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_HIL_SENSOR_LEN? msg->len : MAVLINK_MSG_ID_HIL_SENSOR_LEN; - memset(hil_sensor, 0, MAVLINK_MSG_ID_HIL_SENSOR_LEN); - memcpy(hil_sensor, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_hil_state.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_hil_state.h deleted file mode 100644 index 4766c920..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_hil_state.h +++ /dev/null @@ -1,588 +0,0 @@ -#pragma once -// MESSAGE HIL_STATE PACKING - -#define MAVLINK_MSG_ID_HIL_STATE 90 - - -typedef struct __mavlink_hil_state_t { - uint64_t time_usec; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/ - float roll; /*< [rad] Roll angle*/ - float pitch; /*< [rad] Pitch angle*/ - float yaw; /*< [rad] Yaw angle*/ - float rollspeed; /*< [rad/s] Body frame roll / phi angular speed*/ - float pitchspeed; /*< [rad/s] Body frame pitch / theta angular speed*/ - float yawspeed; /*< [rad/s] Body frame yaw / psi angular speed*/ - int32_t lat; /*< [degE7] Latitude*/ - int32_t lon; /*< [degE7] Longitude*/ - int32_t alt; /*< [mm] Altitude*/ - int16_t vx; /*< [cm/s] Ground X Speed (Latitude)*/ - int16_t vy; /*< [cm/s] Ground Y Speed (Longitude)*/ - int16_t vz; /*< [cm/s] Ground Z Speed (Altitude)*/ - int16_t xacc; /*< [mG] X acceleration*/ - int16_t yacc; /*< [mG] Y acceleration*/ - int16_t zacc; /*< [mG] Z acceleration*/ -} mavlink_hil_state_t; - -#define MAVLINK_MSG_ID_HIL_STATE_LEN 56 -#define MAVLINK_MSG_ID_HIL_STATE_MIN_LEN 56 -#define MAVLINK_MSG_ID_90_LEN 56 -#define MAVLINK_MSG_ID_90_MIN_LEN 56 - -#define MAVLINK_MSG_ID_HIL_STATE_CRC 183 -#define MAVLINK_MSG_ID_90_CRC 183 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_HIL_STATE { \ - 90, \ - "HIL_STATE", \ - 16, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_state_t, time_usec) }, \ - { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_hil_state_t, roll) }, \ - { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_hil_state_t, pitch) }, \ - { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_hil_state_t, yaw) }, \ - { "rollspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_hil_state_t, rollspeed) }, \ - { "pitchspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_hil_state_t, pitchspeed) }, \ - { "yawspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_hil_state_t, yawspeed) }, \ - { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 32, offsetof(mavlink_hil_state_t, lat) }, \ - { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 36, offsetof(mavlink_hil_state_t, lon) }, \ - { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 40, offsetof(mavlink_hil_state_t, alt) }, \ - { "vx", NULL, MAVLINK_TYPE_INT16_T, 0, 44, offsetof(mavlink_hil_state_t, vx) }, \ - { "vy", NULL, MAVLINK_TYPE_INT16_T, 0, 46, offsetof(mavlink_hil_state_t, vy) }, \ - { "vz", NULL, MAVLINK_TYPE_INT16_T, 0, 48, offsetof(mavlink_hil_state_t, vz) }, \ - { "xacc", NULL, MAVLINK_TYPE_INT16_T, 0, 50, offsetof(mavlink_hil_state_t, xacc) }, \ - { "yacc", NULL, MAVLINK_TYPE_INT16_T, 0, 52, offsetof(mavlink_hil_state_t, yacc) }, \ - { "zacc", NULL, MAVLINK_TYPE_INT16_T, 0, 54, offsetof(mavlink_hil_state_t, zacc) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_HIL_STATE { \ - "HIL_STATE", \ - 16, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_state_t, time_usec) }, \ - { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_hil_state_t, roll) }, \ - { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_hil_state_t, pitch) }, \ - { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_hil_state_t, yaw) }, \ - { "rollspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_hil_state_t, rollspeed) }, \ - { "pitchspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_hil_state_t, pitchspeed) }, \ - { "yawspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_hil_state_t, yawspeed) }, \ - { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 32, offsetof(mavlink_hil_state_t, lat) }, \ - { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 36, offsetof(mavlink_hil_state_t, lon) }, \ - { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 40, offsetof(mavlink_hil_state_t, alt) }, \ - { "vx", NULL, MAVLINK_TYPE_INT16_T, 0, 44, offsetof(mavlink_hil_state_t, vx) }, \ - { "vy", NULL, MAVLINK_TYPE_INT16_T, 0, 46, offsetof(mavlink_hil_state_t, vy) }, \ - { "vz", NULL, MAVLINK_TYPE_INT16_T, 0, 48, offsetof(mavlink_hil_state_t, vz) }, \ - { "xacc", NULL, MAVLINK_TYPE_INT16_T, 0, 50, offsetof(mavlink_hil_state_t, xacc) }, \ - { "yacc", NULL, MAVLINK_TYPE_INT16_T, 0, 52, offsetof(mavlink_hil_state_t, yacc) }, \ - { "zacc", NULL, MAVLINK_TYPE_INT16_T, 0, 54, offsetof(mavlink_hil_state_t, zacc) }, \ - } \ -} -#endif - -/** - * @brief Pack a hil_state message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @param roll [rad] Roll angle - * @param pitch [rad] Pitch angle - * @param yaw [rad] Yaw angle - * @param rollspeed [rad/s] Body frame roll / phi angular speed - * @param pitchspeed [rad/s] Body frame pitch / theta angular speed - * @param yawspeed [rad/s] Body frame yaw / psi angular speed - * @param lat [degE7] Latitude - * @param lon [degE7] Longitude - * @param alt [mm] Altitude - * @param vx [cm/s] Ground X Speed (Latitude) - * @param vy [cm/s] Ground Y Speed (Longitude) - * @param vz [cm/s] Ground Z Speed (Altitude) - * @param xacc [mG] X acceleration - * @param yacc [mG] Y acceleration - * @param zacc [mG] Z acceleration - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_hil_state_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint64_t time_usec, float roll, float pitch, float yaw, float rollspeed, float pitchspeed, float yawspeed, int32_t lat, int32_t lon, int32_t alt, int16_t vx, int16_t vy, int16_t vz, int16_t xacc, int16_t yacc, int16_t zacc) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_HIL_STATE_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, roll); - _mav_put_float(buf, 12, pitch); - _mav_put_float(buf, 16, yaw); - _mav_put_float(buf, 20, rollspeed); - _mav_put_float(buf, 24, pitchspeed); - _mav_put_float(buf, 28, yawspeed); - _mav_put_int32_t(buf, 32, lat); - _mav_put_int32_t(buf, 36, lon); - _mav_put_int32_t(buf, 40, alt); - _mav_put_int16_t(buf, 44, vx); - _mav_put_int16_t(buf, 46, vy); - _mav_put_int16_t(buf, 48, vz); - _mav_put_int16_t(buf, 50, xacc); - _mav_put_int16_t(buf, 52, yacc); - _mav_put_int16_t(buf, 54, zacc); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIL_STATE_LEN); -#else - mavlink_hil_state_t packet; - packet.time_usec = time_usec; - packet.roll = roll; - packet.pitch = pitch; - packet.yaw = yaw; - packet.rollspeed = rollspeed; - packet.pitchspeed = pitchspeed; - packet.yawspeed = yawspeed; - packet.lat = lat; - packet.lon = lon; - packet.alt = alt; - packet.vx = vx; - packet.vy = vy; - packet.vz = vz; - packet.xacc = xacc; - packet.yacc = yacc; - packet.zacc = zacc; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIL_STATE_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_HIL_STATE; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HIL_STATE_MIN_LEN, MAVLINK_MSG_ID_HIL_STATE_LEN, MAVLINK_MSG_ID_HIL_STATE_CRC); -} - -/** - * @brief Pack a hil_state message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @param roll [rad] Roll angle - * @param pitch [rad] Pitch angle - * @param yaw [rad] Yaw angle - * @param rollspeed [rad/s] Body frame roll / phi angular speed - * @param pitchspeed [rad/s] Body frame pitch / theta angular speed - * @param yawspeed [rad/s] Body frame yaw / psi angular speed - * @param lat [degE7] Latitude - * @param lon [degE7] Longitude - * @param alt [mm] Altitude - * @param vx [cm/s] Ground X Speed (Latitude) - * @param vy [cm/s] Ground Y Speed (Longitude) - * @param vz [cm/s] Ground Z Speed (Altitude) - * @param xacc [mG] X acceleration - * @param yacc [mG] Y acceleration - * @param zacc [mG] Z acceleration - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_hil_state_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint64_t time_usec,float roll,float pitch,float yaw,float rollspeed,float pitchspeed,float yawspeed,int32_t lat,int32_t lon,int32_t alt,int16_t vx,int16_t vy,int16_t vz,int16_t xacc,int16_t yacc,int16_t zacc) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_HIL_STATE_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, roll); - _mav_put_float(buf, 12, pitch); - _mav_put_float(buf, 16, yaw); - _mav_put_float(buf, 20, rollspeed); - _mav_put_float(buf, 24, pitchspeed); - _mav_put_float(buf, 28, yawspeed); - _mav_put_int32_t(buf, 32, lat); - _mav_put_int32_t(buf, 36, lon); - _mav_put_int32_t(buf, 40, alt); - _mav_put_int16_t(buf, 44, vx); - _mav_put_int16_t(buf, 46, vy); - _mav_put_int16_t(buf, 48, vz); - _mav_put_int16_t(buf, 50, xacc); - _mav_put_int16_t(buf, 52, yacc); - _mav_put_int16_t(buf, 54, zacc); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIL_STATE_LEN); -#else - mavlink_hil_state_t packet; - packet.time_usec = time_usec; - packet.roll = roll; - packet.pitch = pitch; - packet.yaw = yaw; - packet.rollspeed = rollspeed; - packet.pitchspeed = pitchspeed; - packet.yawspeed = yawspeed; - packet.lat = lat; - packet.lon = lon; - packet.alt = alt; - packet.vx = vx; - packet.vy = vy; - packet.vz = vz; - packet.xacc = xacc; - packet.yacc = yacc; - packet.zacc = zacc; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIL_STATE_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_HIL_STATE; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HIL_STATE_MIN_LEN, MAVLINK_MSG_ID_HIL_STATE_LEN, MAVLINK_MSG_ID_HIL_STATE_CRC); -} - -/** - * @brief Encode a hil_state struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param hil_state C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_hil_state_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_hil_state_t* hil_state) -{ - return mavlink_msg_hil_state_pack(system_id, component_id, msg, hil_state->time_usec, hil_state->roll, hil_state->pitch, hil_state->yaw, hil_state->rollspeed, hil_state->pitchspeed, hil_state->yawspeed, hil_state->lat, hil_state->lon, hil_state->alt, hil_state->vx, hil_state->vy, hil_state->vz, hil_state->xacc, hil_state->yacc, hil_state->zacc); -} - -/** - * @brief Encode a hil_state struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param hil_state C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_hil_state_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_hil_state_t* hil_state) -{ - return mavlink_msg_hil_state_pack_chan(system_id, component_id, chan, msg, hil_state->time_usec, hil_state->roll, hil_state->pitch, hil_state->yaw, hil_state->rollspeed, hil_state->pitchspeed, hil_state->yawspeed, hil_state->lat, hil_state->lon, hil_state->alt, hil_state->vx, hil_state->vy, hil_state->vz, hil_state->xacc, hil_state->yacc, hil_state->zacc); -} - -/** - * @brief Send a hil_state message - * @param chan MAVLink channel to send the message - * - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @param roll [rad] Roll angle - * @param pitch [rad] Pitch angle - * @param yaw [rad] Yaw angle - * @param rollspeed [rad/s] Body frame roll / phi angular speed - * @param pitchspeed [rad/s] Body frame pitch / theta angular speed - * @param yawspeed [rad/s] Body frame yaw / psi angular speed - * @param lat [degE7] Latitude - * @param lon [degE7] Longitude - * @param alt [mm] Altitude - * @param vx [cm/s] Ground X Speed (Latitude) - * @param vy [cm/s] Ground Y Speed (Longitude) - * @param vz [cm/s] Ground Z Speed (Altitude) - * @param xacc [mG] X acceleration - * @param yacc [mG] Y acceleration - * @param zacc [mG] Z acceleration - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_hil_state_send(mavlink_channel_t chan, uint64_t time_usec, float roll, float pitch, float yaw, float rollspeed, float pitchspeed, float yawspeed, int32_t lat, int32_t lon, int32_t alt, int16_t vx, int16_t vy, int16_t vz, int16_t xacc, int16_t yacc, int16_t zacc) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_HIL_STATE_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, roll); - _mav_put_float(buf, 12, pitch); - _mav_put_float(buf, 16, yaw); - _mav_put_float(buf, 20, rollspeed); - _mav_put_float(buf, 24, pitchspeed); - _mav_put_float(buf, 28, yawspeed); - _mav_put_int32_t(buf, 32, lat); - _mav_put_int32_t(buf, 36, lon); - _mav_put_int32_t(buf, 40, alt); - _mav_put_int16_t(buf, 44, vx); - _mav_put_int16_t(buf, 46, vy); - _mav_put_int16_t(buf, 48, vz); - _mav_put_int16_t(buf, 50, xacc); - _mav_put_int16_t(buf, 52, yacc); - _mav_put_int16_t(buf, 54, zacc); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE, buf, MAVLINK_MSG_ID_HIL_STATE_MIN_LEN, MAVLINK_MSG_ID_HIL_STATE_LEN, MAVLINK_MSG_ID_HIL_STATE_CRC); -#else - mavlink_hil_state_t packet; - packet.time_usec = time_usec; - packet.roll = roll; - packet.pitch = pitch; - packet.yaw = yaw; - packet.rollspeed = rollspeed; - packet.pitchspeed = pitchspeed; - packet.yawspeed = yawspeed; - packet.lat = lat; - packet.lon = lon; - packet.alt = alt; - packet.vx = vx; - packet.vy = vy; - packet.vz = vz; - packet.xacc = xacc; - packet.yacc = yacc; - packet.zacc = zacc; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE, (const char *)&packet, MAVLINK_MSG_ID_HIL_STATE_MIN_LEN, MAVLINK_MSG_ID_HIL_STATE_LEN, MAVLINK_MSG_ID_HIL_STATE_CRC); -#endif -} - -/** - * @brief Send a hil_state message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_hil_state_send_struct(mavlink_channel_t chan, const mavlink_hil_state_t* hil_state) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_hil_state_send(chan, hil_state->time_usec, hil_state->roll, hil_state->pitch, hil_state->yaw, hil_state->rollspeed, hil_state->pitchspeed, hil_state->yawspeed, hil_state->lat, hil_state->lon, hil_state->alt, hil_state->vx, hil_state->vy, hil_state->vz, hil_state->xacc, hil_state->yacc, hil_state->zacc); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE, (const char *)hil_state, MAVLINK_MSG_ID_HIL_STATE_MIN_LEN, MAVLINK_MSG_ID_HIL_STATE_LEN, MAVLINK_MSG_ID_HIL_STATE_CRC); -#endif -} - -#if MAVLINK_MSG_ID_HIL_STATE_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_hil_state_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, float roll, float pitch, float yaw, float rollspeed, float pitchspeed, float yawspeed, int32_t lat, int32_t lon, int32_t alt, int16_t vx, int16_t vy, int16_t vz, int16_t xacc, int16_t yacc, int16_t zacc) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, roll); - _mav_put_float(buf, 12, pitch); - _mav_put_float(buf, 16, yaw); - _mav_put_float(buf, 20, rollspeed); - _mav_put_float(buf, 24, pitchspeed); - _mav_put_float(buf, 28, yawspeed); - _mav_put_int32_t(buf, 32, lat); - _mav_put_int32_t(buf, 36, lon); - _mav_put_int32_t(buf, 40, alt); - _mav_put_int16_t(buf, 44, vx); - _mav_put_int16_t(buf, 46, vy); - _mav_put_int16_t(buf, 48, vz); - _mav_put_int16_t(buf, 50, xacc); - _mav_put_int16_t(buf, 52, yacc); - _mav_put_int16_t(buf, 54, zacc); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE, buf, MAVLINK_MSG_ID_HIL_STATE_MIN_LEN, MAVLINK_MSG_ID_HIL_STATE_LEN, MAVLINK_MSG_ID_HIL_STATE_CRC); -#else - mavlink_hil_state_t *packet = (mavlink_hil_state_t *)msgbuf; - packet->time_usec = time_usec; - packet->roll = roll; - packet->pitch = pitch; - packet->yaw = yaw; - packet->rollspeed = rollspeed; - packet->pitchspeed = pitchspeed; - packet->yawspeed = yawspeed; - packet->lat = lat; - packet->lon = lon; - packet->alt = alt; - packet->vx = vx; - packet->vy = vy; - packet->vz = vz; - packet->xacc = xacc; - packet->yacc = yacc; - packet->zacc = zacc; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE, (const char *)packet, MAVLINK_MSG_ID_HIL_STATE_MIN_LEN, MAVLINK_MSG_ID_HIL_STATE_LEN, MAVLINK_MSG_ID_HIL_STATE_CRC); -#endif -} -#endif - -#endif - -// MESSAGE HIL_STATE UNPACKING - - -/** - * @brief Get field time_usec from hil_state message - * - * @return [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - */ -static inline uint64_t mavlink_msg_hil_state_get_time_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field roll from hil_state message - * - * @return [rad] Roll angle - */ -static inline float mavlink_msg_hil_state_get_roll(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field pitch from hil_state message - * - * @return [rad] Pitch angle - */ -static inline float mavlink_msg_hil_state_get_pitch(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field yaw from hil_state message - * - * @return [rad] Yaw angle - */ -static inline float mavlink_msg_hil_state_get_yaw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field rollspeed from hil_state message - * - * @return [rad/s] Body frame roll / phi angular speed - */ -static inline float mavlink_msg_hil_state_get_rollspeed(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Get field pitchspeed from hil_state message - * - * @return [rad/s] Body frame pitch / theta angular speed - */ -static inline float mavlink_msg_hil_state_get_pitchspeed(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Get field yawspeed from hil_state message - * - * @return [rad/s] Body frame yaw / psi angular speed - */ -static inline float mavlink_msg_hil_state_get_yawspeed(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 28); -} - -/** - * @brief Get field lat from hil_state message - * - * @return [degE7] Latitude - */ -static inline int32_t mavlink_msg_hil_state_get_lat(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 32); -} - -/** - * @brief Get field lon from hil_state message - * - * @return [degE7] Longitude - */ -static inline int32_t mavlink_msg_hil_state_get_lon(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 36); -} - -/** - * @brief Get field alt from hil_state message - * - * @return [mm] Altitude - */ -static inline int32_t mavlink_msg_hil_state_get_alt(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 40); -} - -/** - * @brief Get field vx from hil_state message - * - * @return [cm/s] Ground X Speed (Latitude) - */ -static inline int16_t mavlink_msg_hil_state_get_vx(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 44); -} - -/** - * @brief Get field vy from hil_state message - * - * @return [cm/s] Ground Y Speed (Longitude) - */ -static inline int16_t mavlink_msg_hil_state_get_vy(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 46); -} - -/** - * @brief Get field vz from hil_state message - * - * @return [cm/s] Ground Z Speed (Altitude) - */ -static inline int16_t mavlink_msg_hil_state_get_vz(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 48); -} - -/** - * @brief Get field xacc from hil_state message - * - * @return [mG] X acceleration - */ -static inline int16_t mavlink_msg_hil_state_get_xacc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 50); -} - -/** - * @brief Get field yacc from hil_state message - * - * @return [mG] Y acceleration - */ -static inline int16_t mavlink_msg_hil_state_get_yacc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 52); -} - -/** - * @brief Get field zacc from hil_state message - * - * @return [mG] Z acceleration - */ -static inline int16_t mavlink_msg_hil_state_get_zacc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 54); -} - -/** - * @brief Decode a hil_state message into a struct - * - * @param msg The message to decode - * @param hil_state C-struct to decode the message contents into - */ -static inline void mavlink_msg_hil_state_decode(const mavlink_message_t* msg, mavlink_hil_state_t* hil_state) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - hil_state->time_usec = mavlink_msg_hil_state_get_time_usec(msg); - hil_state->roll = mavlink_msg_hil_state_get_roll(msg); - hil_state->pitch = mavlink_msg_hil_state_get_pitch(msg); - hil_state->yaw = mavlink_msg_hil_state_get_yaw(msg); - hil_state->rollspeed = mavlink_msg_hil_state_get_rollspeed(msg); - hil_state->pitchspeed = mavlink_msg_hil_state_get_pitchspeed(msg); - hil_state->yawspeed = mavlink_msg_hil_state_get_yawspeed(msg); - hil_state->lat = mavlink_msg_hil_state_get_lat(msg); - hil_state->lon = mavlink_msg_hil_state_get_lon(msg); - hil_state->alt = mavlink_msg_hil_state_get_alt(msg); - hil_state->vx = mavlink_msg_hil_state_get_vx(msg); - hil_state->vy = mavlink_msg_hil_state_get_vy(msg); - hil_state->vz = mavlink_msg_hil_state_get_vz(msg); - hil_state->xacc = mavlink_msg_hil_state_get_xacc(msg); - hil_state->yacc = mavlink_msg_hil_state_get_yacc(msg); - hil_state->zacc = mavlink_msg_hil_state_get_zacc(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_HIL_STATE_LEN? msg->len : MAVLINK_MSG_ID_HIL_STATE_LEN; - memset(hil_state, 0, MAVLINK_MSG_ID_HIL_STATE_LEN); - memcpy(hil_state, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_hil_state_quaternion.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_hil_state_quaternion.h deleted file mode 100644 index 856603c5..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_hil_state_quaternion.h +++ /dev/null @@ -1,580 +0,0 @@ -#pragma once -// MESSAGE HIL_STATE_QUATERNION PACKING - -#define MAVLINK_MSG_ID_HIL_STATE_QUATERNION 115 - - -typedef struct __mavlink_hil_state_quaternion_t { - uint64_t time_usec; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/ - float attitude_quaternion[4]; /*< Vehicle attitude expressed as normalized quaternion in w, x, y, z order (with 1 0 0 0 being the null-rotation)*/ - float rollspeed; /*< [rad/s] Body frame roll / phi angular speed*/ - float pitchspeed; /*< [rad/s] Body frame pitch / theta angular speed*/ - float yawspeed; /*< [rad/s] Body frame yaw / psi angular speed*/ - int32_t lat; /*< [degE7] Latitude*/ - int32_t lon; /*< [degE7] Longitude*/ - int32_t alt; /*< [mm] Altitude*/ - int16_t vx; /*< [cm/s] Ground X Speed (Latitude)*/ - int16_t vy; /*< [cm/s] Ground Y Speed (Longitude)*/ - int16_t vz; /*< [cm/s] Ground Z Speed (Altitude)*/ - uint16_t ind_airspeed; /*< [cm/s] Indicated airspeed*/ - uint16_t true_airspeed; /*< [cm/s] True airspeed*/ - int16_t xacc; /*< [mG] X acceleration*/ - int16_t yacc; /*< [mG] Y acceleration*/ - int16_t zacc; /*< [mG] Z acceleration*/ -} mavlink_hil_state_quaternion_t; - -#define MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN 64 -#define MAVLINK_MSG_ID_HIL_STATE_QUATERNION_MIN_LEN 64 -#define MAVLINK_MSG_ID_115_LEN 64 -#define MAVLINK_MSG_ID_115_MIN_LEN 64 - -#define MAVLINK_MSG_ID_HIL_STATE_QUATERNION_CRC 4 -#define MAVLINK_MSG_ID_115_CRC 4 - -#define MAVLINK_MSG_HIL_STATE_QUATERNION_FIELD_ATTITUDE_QUATERNION_LEN 4 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_HIL_STATE_QUATERNION { \ - 115, \ - "HIL_STATE_QUATERNION", \ - 16, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_state_quaternion_t, time_usec) }, \ - { "attitude_quaternion", NULL, MAVLINK_TYPE_FLOAT, 4, 8, offsetof(mavlink_hil_state_quaternion_t, attitude_quaternion) }, \ - { "rollspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_hil_state_quaternion_t, rollspeed) }, \ - { "pitchspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_hil_state_quaternion_t, pitchspeed) }, \ - { "yawspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_hil_state_quaternion_t, yawspeed) }, \ - { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 36, offsetof(mavlink_hil_state_quaternion_t, lat) }, \ - { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 40, offsetof(mavlink_hil_state_quaternion_t, lon) }, \ - { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 44, offsetof(mavlink_hil_state_quaternion_t, alt) }, \ - { "vx", NULL, MAVLINK_TYPE_INT16_T, 0, 48, offsetof(mavlink_hil_state_quaternion_t, vx) }, \ - { "vy", NULL, MAVLINK_TYPE_INT16_T, 0, 50, offsetof(mavlink_hil_state_quaternion_t, vy) }, \ - { "vz", NULL, MAVLINK_TYPE_INT16_T, 0, 52, offsetof(mavlink_hil_state_quaternion_t, vz) }, \ - { "ind_airspeed", NULL, MAVLINK_TYPE_UINT16_T, 0, 54, offsetof(mavlink_hil_state_quaternion_t, ind_airspeed) }, \ - { "true_airspeed", NULL, MAVLINK_TYPE_UINT16_T, 0, 56, offsetof(mavlink_hil_state_quaternion_t, true_airspeed) }, \ - { "xacc", NULL, MAVLINK_TYPE_INT16_T, 0, 58, offsetof(mavlink_hil_state_quaternion_t, xacc) }, \ - { "yacc", NULL, MAVLINK_TYPE_INT16_T, 0, 60, offsetof(mavlink_hil_state_quaternion_t, yacc) }, \ - { "zacc", NULL, MAVLINK_TYPE_INT16_T, 0, 62, offsetof(mavlink_hil_state_quaternion_t, zacc) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_HIL_STATE_QUATERNION { \ - "HIL_STATE_QUATERNION", \ - 16, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_state_quaternion_t, time_usec) }, \ - { "attitude_quaternion", NULL, MAVLINK_TYPE_FLOAT, 4, 8, offsetof(mavlink_hil_state_quaternion_t, attitude_quaternion) }, \ - { "rollspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_hil_state_quaternion_t, rollspeed) }, \ - { "pitchspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_hil_state_quaternion_t, pitchspeed) }, \ - { "yawspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_hil_state_quaternion_t, yawspeed) }, \ - { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 36, offsetof(mavlink_hil_state_quaternion_t, lat) }, \ - { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 40, offsetof(mavlink_hil_state_quaternion_t, lon) }, \ - { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 44, offsetof(mavlink_hil_state_quaternion_t, alt) }, \ - { "vx", NULL, MAVLINK_TYPE_INT16_T, 0, 48, offsetof(mavlink_hil_state_quaternion_t, vx) }, \ - { "vy", NULL, MAVLINK_TYPE_INT16_T, 0, 50, offsetof(mavlink_hil_state_quaternion_t, vy) }, \ - { "vz", NULL, MAVLINK_TYPE_INT16_T, 0, 52, offsetof(mavlink_hil_state_quaternion_t, vz) }, \ - { "ind_airspeed", NULL, MAVLINK_TYPE_UINT16_T, 0, 54, offsetof(mavlink_hil_state_quaternion_t, ind_airspeed) }, \ - { "true_airspeed", NULL, MAVLINK_TYPE_UINT16_T, 0, 56, offsetof(mavlink_hil_state_quaternion_t, true_airspeed) }, \ - { "xacc", NULL, MAVLINK_TYPE_INT16_T, 0, 58, offsetof(mavlink_hil_state_quaternion_t, xacc) }, \ - { "yacc", NULL, MAVLINK_TYPE_INT16_T, 0, 60, offsetof(mavlink_hil_state_quaternion_t, yacc) }, \ - { "zacc", NULL, MAVLINK_TYPE_INT16_T, 0, 62, offsetof(mavlink_hil_state_quaternion_t, zacc) }, \ - } \ -} -#endif - -/** - * @brief Pack a hil_state_quaternion message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @param attitude_quaternion Vehicle attitude expressed as normalized quaternion in w, x, y, z order (with 1 0 0 0 being the null-rotation) - * @param rollspeed [rad/s] Body frame roll / phi angular speed - * @param pitchspeed [rad/s] Body frame pitch / theta angular speed - * @param yawspeed [rad/s] Body frame yaw / psi angular speed - * @param lat [degE7] Latitude - * @param lon [degE7] Longitude - * @param alt [mm] Altitude - * @param vx [cm/s] Ground X Speed (Latitude) - * @param vy [cm/s] Ground Y Speed (Longitude) - * @param vz [cm/s] Ground Z Speed (Altitude) - * @param ind_airspeed [cm/s] Indicated airspeed - * @param true_airspeed [cm/s] True airspeed - * @param xacc [mG] X acceleration - * @param yacc [mG] Y acceleration - * @param zacc [mG] Z acceleration - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_hil_state_quaternion_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint64_t time_usec, const float *attitude_quaternion, float rollspeed, float pitchspeed, float yawspeed, int32_t lat, int32_t lon, int32_t alt, int16_t vx, int16_t vy, int16_t vz, uint16_t ind_airspeed, uint16_t true_airspeed, int16_t xacc, int16_t yacc, int16_t zacc) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 24, rollspeed); - _mav_put_float(buf, 28, pitchspeed); - _mav_put_float(buf, 32, yawspeed); - _mav_put_int32_t(buf, 36, lat); - _mav_put_int32_t(buf, 40, lon); - _mav_put_int32_t(buf, 44, alt); - _mav_put_int16_t(buf, 48, vx); - _mav_put_int16_t(buf, 50, vy); - _mav_put_int16_t(buf, 52, vz); - _mav_put_uint16_t(buf, 54, ind_airspeed); - _mav_put_uint16_t(buf, 56, true_airspeed); - _mav_put_int16_t(buf, 58, xacc); - _mav_put_int16_t(buf, 60, yacc); - _mav_put_int16_t(buf, 62, zacc); - _mav_put_float_array(buf, 8, attitude_quaternion, 4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN); -#else - mavlink_hil_state_quaternion_t packet; - packet.time_usec = time_usec; - packet.rollspeed = rollspeed; - packet.pitchspeed = pitchspeed; - packet.yawspeed = yawspeed; - packet.lat = lat; - packet.lon = lon; - packet.alt = alt; - packet.vx = vx; - packet.vy = vy; - packet.vz = vz; - packet.ind_airspeed = ind_airspeed; - packet.true_airspeed = true_airspeed; - packet.xacc = xacc; - packet.yacc = yacc; - packet.zacc = zacc; - mav_array_memcpy(packet.attitude_quaternion, attitude_quaternion, sizeof(float)*4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_HIL_STATE_QUATERNION; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_MIN_LEN, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_CRC); -} - -/** - * @brief Pack a hil_state_quaternion message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @param attitude_quaternion Vehicle attitude expressed as normalized quaternion in w, x, y, z order (with 1 0 0 0 being the null-rotation) - * @param rollspeed [rad/s] Body frame roll / phi angular speed - * @param pitchspeed [rad/s] Body frame pitch / theta angular speed - * @param yawspeed [rad/s] Body frame yaw / psi angular speed - * @param lat [degE7] Latitude - * @param lon [degE7] Longitude - * @param alt [mm] Altitude - * @param vx [cm/s] Ground X Speed (Latitude) - * @param vy [cm/s] Ground Y Speed (Longitude) - * @param vz [cm/s] Ground Z Speed (Altitude) - * @param ind_airspeed [cm/s] Indicated airspeed - * @param true_airspeed [cm/s] True airspeed - * @param xacc [mG] X acceleration - * @param yacc [mG] Y acceleration - * @param zacc [mG] Z acceleration - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_hil_state_quaternion_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint64_t time_usec,const float *attitude_quaternion,float rollspeed,float pitchspeed,float yawspeed,int32_t lat,int32_t lon,int32_t alt,int16_t vx,int16_t vy,int16_t vz,uint16_t ind_airspeed,uint16_t true_airspeed,int16_t xacc,int16_t yacc,int16_t zacc) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 24, rollspeed); - _mav_put_float(buf, 28, pitchspeed); - _mav_put_float(buf, 32, yawspeed); - _mav_put_int32_t(buf, 36, lat); - _mav_put_int32_t(buf, 40, lon); - _mav_put_int32_t(buf, 44, alt); - _mav_put_int16_t(buf, 48, vx); - _mav_put_int16_t(buf, 50, vy); - _mav_put_int16_t(buf, 52, vz); - _mav_put_uint16_t(buf, 54, ind_airspeed); - _mav_put_uint16_t(buf, 56, true_airspeed); - _mav_put_int16_t(buf, 58, xacc); - _mav_put_int16_t(buf, 60, yacc); - _mav_put_int16_t(buf, 62, zacc); - _mav_put_float_array(buf, 8, attitude_quaternion, 4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN); -#else - mavlink_hil_state_quaternion_t packet; - packet.time_usec = time_usec; - packet.rollspeed = rollspeed; - packet.pitchspeed = pitchspeed; - packet.yawspeed = yawspeed; - packet.lat = lat; - packet.lon = lon; - packet.alt = alt; - packet.vx = vx; - packet.vy = vy; - packet.vz = vz; - packet.ind_airspeed = ind_airspeed; - packet.true_airspeed = true_airspeed; - packet.xacc = xacc; - packet.yacc = yacc; - packet.zacc = zacc; - mav_array_memcpy(packet.attitude_quaternion, attitude_quaternion, sizeof(float)*4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_HIL_STATE_QUATERNION; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_MIN_LEN, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_CRC); -} - -/** - * @brief Encode a hil_state_quaternion struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param hil_state_quaternion C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_hil_state_quaternion_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_hil_state_quaternion_t* hil_state_quaternion) -{ - return mavlink_msg_hil_state_quaternion_pack(system_id, component_id, msg, hil_state_quaternion->time_usec, hil_state_quaternion->attitude_quaternion, hil_state_quaternion->rollspeed, hil_state_quaternion->pitchspeed, hil_state_quaternion->yawspeed, hil_state_quaternion->lat, hil_state_quaternion->lon, hil_state_quaternion->alt, hil_state_quaternion->vx, hil_state_quaternion->vy, hil_state_quaternion->vz, hil_state_quaternion->ind_airspeed, hil_state_quaternion->true_airspeed, hil_state_quaternion->xacc, hil_state_quaternion->yacc, hil_state_quaternion->zacc); -} - -/** - * @brief Encode a hil_state_quaternion struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param hil_state_quaternion C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_hil_state_quaternion_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_hil_state_quaternion_t* hil_state_quaternion) -{ - return mavlink_msg_hil_state_quaternion_pack_chan(system_id, component_id, chan, msg, hil_state_quaternion->time_usec, hil_state_quaternion->attitude_quaternion, hil_state_quaternion->rollspeed, hil_state_quaternion->pitchspeed, hil_state_quaternion->yawspeed, hil_state_quaternion->lat, hil_state_quaternion->lon, hil_state_quaternion->alt, hil_state_quaternion->vx, hil_state_quaternion->vy, hil_state_quaternion->vz, hil_state_quaternion->ind_airspeed, hil_state_quaternion->true_airspeed, hil_state_quaternion->xacc, hil_state_quaternion->yacc, hil_state_quaternion->zacc); -} - -/** - * @brief Send a hil_state_quaternion message - * @param chan MAVLink channel to send the message - * - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @param attitude_quaternion Vehicle attitude expressed as normalized quaternion in w, x, y, z order (with 1 0 0 0 being the null-rotation) - * @param rollspeed [rad/s] Body frame roll / phi angular speed - * @param pitchspeed [rad/s] Body frame pitch / theta angular speed - * @param yawspeed [rad/s] Body frame yaw / psi angular speed - * @param lat [degE7] Latitude - * @param lon [degE7] Longitude - * @param alt [mm] Altitude - * @param vx [cm/s] Ground X Speed (Latitude) - * @param vy [cm/s] Ground Y Speed (Longitude) - * @param vz [cm/s] Ground Z Speed (Altitude) - * @param ind_airspeed [cm/s] Indicated airspeed - * @param true_airspeed [cm/s] True airspeed - * @param xacc [mG] X acceleration - * @param yacc [mG] Y acceleration - * @param zacc [mG] Z acceleration - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_hil_state_quaternion_send(mavlink_channel_t chan, uint64_t time_usec, const float *attitude_quaternion, float rollspeed, float pitchspeed, float yawspeed, int32_t lat, int32_t lon, int32_t alt, int16_t vx, int16_t vy, int16_t vz, uint16_t ind_airspeed, uint16_t true_airspeed, int16_t xacc, int16_t yacc, int16_t zacc) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 24, rollspeed); - _mav_put_float(buf, 28, pitchspeed); - _mav_put_float(buf, 32, yawspeed); - _mav_put_int32_t(buf, 36, lat); - _mav_put_int32_t(buf, 40, lon); - _mav_put_int32_t(buf, 44, alt); - _mav_put_int16_t(buf, 48, vx); - _mav_put_int16_t(buf, 50, vy); - _mav_put_int16_t(buf, 52, vz); - _mav_put_uint16_t(buf, 54, ind_airspeed); - _mav_put_uint16_t(buf, 56, true_airspeed); - _mav_put_int16_t(buf, 58, xacc); - _mav_put_int16_t(buf, 60, yacc); - _mav_put_int16_t(buf, 62, zacc); - _mav_put_float_array(buf, 8, attitude_quaternion, 4); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE_QUATERNION, buf, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_MIN_LEN, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_CRC); -#else - mavlink_hil_state_quaternion_t packet; - packet.time_usec = time_usec; - packet.rollspeed = rollspeed; - packet.pitchspeed = pitchspeed; - packet.yawspeed = yawspeed; - packet.lat = lat; - packet.lon = lon; - packet.alt = alt; - packet.vx = vx; - packet.vy = vy; - packet.vz = vz; - packet.ind_airspeed = ind_airspeed; - packet.true_airspeed = true_airspeed; - packet.xacc = xacc; - packet.yacc = yacc; - packet.zacc = zacc; - mav_array_memcpy(packet.attitude_quaternion, attitude_quaternion, sizeof(float)*4); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE_QUATERNION, (const char *)&packet, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_MIN_LEN, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_CRC); -#endif -} - -/** - * @brief Send a hil_state_quaternion message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_hil_state_quaternion_send_struct(mavlink_channel_t chan, const mavlink_hil_state_quaternion_t* hil_state_quaternion) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_hil_state_quaternion_send(chan, hil_state_quaternion->time_usec, hil_state_quaternion->attitude_quaternion, hil_state_quaternion->rollspeed, hil_state_quaternion->pitchspeed, hil_state_quaternion->yawspeed, hil_state_quaternion->lat, hil_state_quaternion->lon, hil_state_quaternion->alt, hil_state_quaternion->vx, hil_state_quaternion->vy, hil_state_quaternion->vz, hil_state_quaternion->ind_airspeed, hil_state_quaternion->true_airspeed, hil_state_quaternion->xacc, hil_state_quaternion->yacc, hil_state_quaternion->zacc); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE_QUATERNION, (const char *)hil_state_quaternion, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_MIN_LEN, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_CRC); -#endif -} - -#if MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_hil_state_quaternion_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, const float *attitude_quaternion, float rollspeed, float pitchspeed, float yawspeed, int32_t lat, int32_t lon, int32_t alt, int16_t vx, int16_t vy, int16_t vz, uint16_t ind_airspeed, uint16_t true_airspeed, int16_t xacc, int16_t yacc, int16_t zacc) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 24, rollspeed); - _mav_put_float(buf, 28, pitchspeed); - _mav_put_float(buf, 32, yawspeed); - _mav_put_int32_t(buf, 36, lat); - _mav_put_int32_t(buf, 40, lon); - _mav_put_int32_t(buf, 44, alt); - _mav_put_int16_t(buf, 48, vx); - _mav_put_int16_t(buf, 50, vy); - _mav_put_int16_t(buf, 52, vz); - _mav_put_uint16_t(buf, 54, ind_airspeed); - _mav_put_uint16_t(buf, 56, true_airspeed); - _mav_put_int16_t(buf, 58, xacc); - _mav_put_int16_t(buf, 60, yacc); - _mav_put_int16_t(buf, 62, zacc); - _mav_put_float_array(buf, 8, attitude_quaternion, 4); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE_QUATERNION, buf, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_MIN_LEN, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_CRC); -#else - mavlink_hil_state_quaternion_t *packet = (mavlink_hil_state_quaternion_t *)msgbuf; - packet->time_usec = time_usec; - packet->rollspeed = rollspeed; - packet->pitchspeed = pitchspeed; - packet->yawspeed = yawspeed; - packet->lat = lat; - packet->lon = lon; - packet->alt = alt; - packet->vx = vx; - packet->vy = vy; - packet->vz = vz; - packet->ind_airspeed = ind_airspeed; - packet->true_airspeed = true_airspeed; - packet->xacc = xacc; - packet->yacc = yacc; - packet->zacc = zacc; - mav_array_memcpy(packet->attitude_quaternion, attitude_quaternion, sizeof(float)*4); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE_QUATERNION, (const char *)packet, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_MIN_LEN, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_CRC); -#endif -} -#endif - -#endif - -// MESSAGE HIL_STATE_QUATERNION UNPACKING - - -/** - * @brief Get field time_usec from hil_state_quaternion message - * - * @return [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - */ -static inline uint64_t mavlink_msg_hil_state_quaternion_get_time_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field attitude_quaternion from hil_state_quaternion message - * - * @return Vehicle attitude expressed as normalized quaternion in w, x, y, z order (with 1 0 0 0 being the null-rotation) - */ -static inline uint16_t mavlink_msg_hil_state_quaternion_get_attitude_quaternion(const mavlink_message_t* msg, float *attitude_quaternion) -{ - return _MAV_RETURN_float_array(msg, attitude_quaternion, 4, 8); -} - -/** - * @brief Get field rollspeed from hil_state_quaternion message - * - * @return [rad/s] Body frame roll / phi angular speed - */ -static inline float mavlink_msg_hil_state_quaternion_get_rollspeed(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Get field pitchspeed from hil_state_quaternion message - * - * @return [rad/s] Body frame pitch / theta angular speed - */ -static inline float mavlink_msg_hil_state_quaternion_get_pitchspeed(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 28); -} - -/** - * @brief Get field yawspeed from hil_state_quaternion message - * - * @return [rad/s] Body frame yaw / psi angular speed - */ -static inline float mavlink_msg_hil_state_quaternion_get_yawspeed(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 32); -} - -/** - * @brief Get field lat from hil_state_quaternion message - * - * @return [degE7] Latitude - */ -static inline int32_t mavlink_msg_hil_state_quaternion_get_lat(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 36); -} - -/** - * @brief Get field lon from hil_state_quaternion message - * - * @return [degE7] Longitude - */ -static inline int32_t mavlink_msg_hil_state_quaternion_get_lon(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 40); -} - -/** - * @brief Get field alt from hil_state_quaternion message - * - * @return [mm] Altitude - */ -static inline int32_t mavlink_msg_hil_state_quaternion_get_alt(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 44); -} - -/** - * @brief Get field vx from hil_state_quaternion message - * - * @return [cm/s] Ground X Speed (Latitude) - */ -static inline int16_t mavlink_msg_hil_state_quaternion_get_vx(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 48); -} - -/** - * @brief Get field vy from hil_state_quaternion message - * - * @return [cm/s] Ground Y Speed (Longitude) - */ -static inline int16_t mavlink_msg_hil_state_quaternion_get_vy(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 50); -} - -/** - * @brief Get field vz from hil_state_quaternion message - * - * @return [cm/s] Ground Z Speed (Altitude) - */ -static inline int16_t mavlink_msg_hil_state_quaternion_get_vz(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 52); -} - -/** - * @brief Get field ind_airspeed from hil_state_quaternion message - * - * @return [cm/s] Indicated airspeed - */ -static inline uint16_t mavlink_msg_hil_state_quaternion_get_ind_airspeed(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 54); -} - -/** - * @brief Get field true_airspeed from hil_state_quaternion message - * - * @return [cm/s] True airspeed - */ -static inline uint16_t mavlink_msg_hil_state_quaternion_get_true_airspeed(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 56); -} - -/** - * @brief Get field xacc from hil_state_quaternion message - * - * @return [mG] X acceleration - */ -static inline int16_t mavlink_msg_hil_state_quaternion_get_xacc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 58); -} - -/** - * @brief Get field yacc from hil_state_quaternion message - * - * @return [mG] Y acceleration - */ -static inline int16_t mavlink_msg_hil_state_quaternion_get_yacc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 60); -} - -/** - * @brief Get field zacc from hil_state_quaternion message - * - * @return [mG] Z acceleration - */ -static inline int16_t mavlink_msg_hil_state_quaternion_get_zacc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 62); -} - -/** - * @brief Decode a hil_state_quaternion message into a struct - * - * @param msg The message to decode - * @param hil_state_quaternion C-struct to decode the message contents into - */ -static inline void mavlink_msg_hil_state_quaternion_decode(const mavlink_message_t* msg, mavlink_hil_state_quaternion_t* hil_state_quaternion) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - hil_state_quaternion->time_usec = mavlink_msg_hil_state_quaternion_get_time_usec(msg); - mavlink_msg_hil_state_quaternion_get_attitude_quaternion(msg, hil_state_quaternion->attitude_quaternion); - hil_state_quaternion->rollspeed = mavlink_msg_hil_state_quaternion_get_rollspeed(msg); - hil_state_quaternion->pitchspeed = mavlink_msg_hil_state_quaternion_get_pitchspeed(msg); - hil_state_quaternion->yawspeed = mavlink_msg_hil_state_quaternion_get_yawspeed(msg); - hil_state_quaternion->lat = mavlink_msg_hil_state_quaternion_get_lat(msg); - hil_state_quaternion->lon = mavlink_msg_hil_state_quaternion_get_lon(msg); - hil_state_quaternion->alt = mavlink_msg_hil_state_quaternion_get_alt(msg); - hil_state_quaternion->vx = mavlink_msg_hil_state_quaternion_get_vx(msg); - hil_state_quaternion->vy = mavlink_msg_hil_state_quaternion_get_vy(msg); - hil_state_quaternion->vz = mavlink_msg_hil_state_quaternion_get_vz(msg); - hil_state_quaternion->ind_airspeed = mavlink_msg_hil_state_quaternion_get_ind_airspeed(msg); - hil_state_quaternion->true_airspeed = mavlink_msg_hil_state_quaternion_get_true_airspeed(msg); - hil_state_quaternion->xacc = mavlink_msg_hil_state_quaternion_get_xacc(msg); - hil_state_quaternion->yacc = mavlink_msg_hil_state_quaternion_get_yacc(msg); - hil_state_quaternion->zacc = mavlink_msg_hil_state_quaternion_get_zacc(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN? msg->len : MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN; - memset(hil_state_quaternion, 0, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN); - memcpy(hil_state_quaternion, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_home_position.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_home_position.h deleted file mode 100644 index 7041396e..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_home_position.h +++ /dev/null @@ -1,475 +0,0 @@ -#pragma once -// MESSAGE HOME_POSITION PACKING - -#define MAVLINK_MSG_ID_HOME_POSITION 242 - -MAVPACKED( -typedef struct __mavlink_home_position_t { - int32_t latitude; /*< [degE7] Latitude (WGS84)*/ - int32_t longitude; /*< [degE7] Longitude (WGS84)*/ - int32_t altitude; /*< [mm] Altitude (MSL). Positive for up.*/ - float x; /*< [m] Local X position of this position in the local coordinate frame (NED)*/ - float y; /*< [m] Local Y position of this position in the local coordinate frame (NED)*/ - float z; /*< [m] Local Z position of this position in the local coordinate frame (NED: positive "down")*/ - float q[4]; /*< - Quaternion indicating world-to-surface-normal and heading transformation of the takeoff position. - Used to indicate the heading and slope of the ground. - All fields should be set to NaN if an accurate quaternion for both heading and surface slope cannot be supplied. - */ - float approach_x; /*< [m] Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.*/ - float approach_y; /*< [m] Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.*/ - float approach_z; /*< [m] Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.*/ - uint64_t time_usec; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/ -}) mavlink_home_position_t; - -#define MAVLINK_MSG_ID_HOME_POSITION_LEN 60 -#define MAVLINK_MSG_ID_HOME_POSITION_MIN_LEN 52 -#define MAVLINK_MSG_ID_242_LEN 60 -#define MAVLINK_MSG_ID_242_MIN_LEN 52 - -#define MAVLINK_MSG_ID_HOME_POSITION_CRC 104 -#define MAVLINK_MSG_ID_242_CRC 104 - -#define MAVLINK_MSG_HOME_POSITION_FIELD_Q_LEN 4 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_HOME_POSITION { \ - 242, \ - "HOME_POSITION", \ - 11, \ - { { "latitude", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_home_position_t, latitude) }, \ - { "longitude", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_home_position_t, longitude) }, \ - { "altitude", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_home_position_t, altitude) }, \ - { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_home_position_t, x) }, \ - { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_home_position_t, y) }, \ - { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_home_position_t, z) }, \ - { "q", NULL, MAVLINK_TYPE_FLOAT, 4, 24, offsetof(mavlink_home_position_t, q) }, \ - { "approach_x", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_home_position_t, approach_x) }, \ - { "approach_y", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_home_position_t, approach_y) }, \ - { "approach_z", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_home_position_t, approach_z) }, \ - { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 52, offsetof(mavlink_home_position_t, time_usec) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_HOME_POSITION { \ - "HOME_POSITION", \ - 11, \ - { { "latitude", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_home_position_t, latitude) }, \ - { "longitude", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_home_position_t, longitude) }, \ - { "altitude", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_home_position_t, altitude) }, \ - { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_home_position_t, x) }, \ - { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_home_position_t, y) }, \ - { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_home_position_t, z) }, \ - { "q", NULL, MAVLINK_TYPE_FLOAT, 4, 24, offsetof(mavlink_home_position_t, q) }, \ - { "approach_x", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_home_position_t, approach_x) }, \ - { "approach_y", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_home_position_t, approach_y) }, \ - { "approach_z", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_home_position_t, approach_z) }, \ - { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 52, offsetof(mavlink_home_position_t, time_usec) }, \ - } \ -} -#endif - -/** - * @brief Pack a home_position message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param latitude [degE7] Latitude (WGS84) - * @param longitude [degE7] Longitude (WGS84) - * @param altitude [mm] Altitude (MSL). Positive for up. - * @param x [m] Local X position of this position in the local coordinate frame (NED) - * @param y [m] Local Y position of this position in the local coordinate frame (NED) - * @param z [m] Local Z position of this position in the local coordinate frame (NED: positive "down") - * @param q - Quaternion indicating world-to-surface-normal and heading transformation of the takeoff position. - Used to indicate the heading and slope of the ground. - All fields should be set to NaN if an accurate quaternion for both heading and surface slope cannot be supplied. - - * @param approach_x [m] Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. - * @param approach_y [m] Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. - * @param approach_z [m] Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_home_position_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - int32_t latitude, int32_t longitude, int32_t altitude, float x, float y, float z, const float *q, float approach_x, float approach_y, float approach_z, uint64_t time_usec) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_HOME_POSITION_LEN]; - _mav_put_int32_t(buf, 0, latitude); - _mav_put_int32_t(buf, 4, longitude); - _mav_put_int32_t(buf, 8, altitude); - _mav_put_float(buf, 12, x); - _mav_put_float(buf, 16, y); - _mav_put_float(buf, 20, z); - _mav_put_float(buf, 40, approach_x); - _mav_put_float(buf, 44, approach_y); - _mav_put_float(buf, 48, approach_z); - _mav_put_uint64_t(buf, 52, time_usec); - _mav_put_float_array(buf, 24, q, 4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HOME_POSITION_LEN); -#else - mavlink_home_position_t packet; - packet.latitude = latitude; - packet.longitude = longitude; - packet.altitude = altitude; - packet.x = x; - packet.y = y; - packet.z = z; - packet.approach_x = approach_x; - packet.approach_y = approach_y; - packet.approach_z = approach_z; - packet.time_usec = time_usec; - mav_array_memcpy(packet.q, q, sizeof(float)*4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HOME_POSITION_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_HOME_POSITION; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HOME_POSITION_MIN_LEN, MAVLINK_MSG_ID_HOME_POSITION_LEN, MAVLINK_MSG_ID_HOME_POSITION_CRC); -} - -/** - * @brief Pack a home_position message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param latitude [degE7] Latitude (WGS84) - * @param longitude [degE7] Longitude (WGS84) - * @param altitude [mm] Altitude (MSL). Positive for up. - * @param x [m] Local X position of this position in the local coordinate frame (NED) - * @param y [m] Local Y position of this position in the local coordinate frame (NED) - * @param z [m] Local Z position of this position in the local coordinate frame (NED: positive "down") - * @param q - Quaternion indicating world-to-surface-normal and heading transformation of the takeoff position. - Used to indicate the heading and slope of the ground. - All fields should be set to NaN if an accurate quaternion for both heading and surface slope cannot be supplied. - - * @param approach_x [m] Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. - * @param approach_y [m] Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. - * @param approach_z [m] Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_home_position_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - int32_t latitude,int32_t longitude,int32_t altitude,float x,float y,float z,const float *q,float approach_x,float approach_y,float approach_z,uint64_t time_usec) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_HOME_POSITION_LEN]; - _mav_put_int32_t(buf, 0, latitude); - _mav_put_int32_t(buf, 4, longitude); - _mav_put_int32_t(buf, 8, altitude); - _mav_put_float(buf, 12, x); - _mav_put_float(buf, 16, y); - _mav_put_float(buf, 20, z); - _mav_put_float(buf, 40, approach_x); - _mav_put_float(buf, 44, approach_y); - _mav_put_float(buf, 48, approach_z); - _mav_put_uint64_t(buf, 52, time_usec); - _mav_put_float_array(buf, 24, q, 4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HOME_POSITION_LEN); -#else - mavlink_home_position_t packet; - packet.latitude = latitude; - packet.longitude = longitude; - packet.altitude = altitude; - packet.x = x; - packet.y = y; - packet.z = z; - packet.approach_x = approach_x; - packet.approach_y = approach_y; - packet.approach_z = approach_z; - packet.time_usec = time_usec; - mav_array_memcpy(packet.q, q, sizeof(float)*4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HOME_POSITION_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_HOME_POSITION; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HOME_POSITION_MIN_LEN, MAVLINK_MSG_ID_HOME_POSITION_LEN, MAVLINK_MSG_ID_HOME_POSITION_CRC); -} - -/** - * @brief Encode a home_position struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param home_position C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_home_position_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_home_position_t* home_position) -{ - return mavlink_msg_home_position_pack(system_id, component_id, msg, home_position->latitude, home_position->longitude, home_position->altitude, home_position->x, home_position->y, home_position->z, home_position->q, home_position->approach_x, home_position->approach_y, home_position->approach_z, home_position->time_usec); -} - -/** - * @brief Encode a home_position struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param home_position C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_home_position_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_home_position_t* home_position) -{ - return mavlink_msg_home_position_pack_chan(system_id, component_id, chan, msg, home_position->latitude, home_position->longitude, home_position->altitude, home_position->x, home_position->y, home_position->z, home_position->q, home_position->approach_x, home_position->approach_y, home_position->approach_z, home_position->time_usec); -} - -/** - * @brief Send a home_position message - * @param chan MAVLink channel to send the message - * - * @param latitude [degE7] Latitude (WGS84) - * @param longitude [degE7] Longitude (WGS84) - * @param altitude [mm] Altitude (MSL). Positive for up. - * @param x [m] Local X position of this position in the local coordinate frame (NED) - * @param y [m] Local Y position of this position in the local coordinate frame (NED) - * @param z [m] Local Z position of this position in the local coordinate frame (NED: positive "down") - * @param q - Quaternion indicating world-to-surface-normal and heading transformation of the takeoff position. - Used to indicate the heading and slope of the ground. - All fields should be set to NaN if an accurate quaternion for both heading and surface slope cannot be supplied. - - * @param approach_x [m] Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. - * @param approach_y [m] Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. - * @param approach_z [m] Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_home_position_send(mavlink_channel_t chan, int32_t latitude, int32_t longitude, int32_t altitude, float x, float y, float z, const float *q, float approach_x, float approach_y, float approach_z, uint64_t time_usec) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_HOME_POSITION_LEN]; - _mav_put_int32_t(buf, 0, latitude); - _mav_put_int32_t(buf, 4, longitude); - _mav_put_int32_t(buf, 8, altitude); - _mav_put_float(buf, 12, x); - _mav_put_float(buf, 16, y); - _mav_put_float(buf, 20, z); - _mav_put_float(buf, 40, approach_x); - _mav_put_float(buf, 44, approach_y); - _mav_put_float(buf, 48, approach_z); - _mav_put_uint64_t(buf, 52, time_usec); - _mav_put_float_array(buf, 24, q, 4); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HOME_POSITION, buf, MAVLINK_MSG_ID_HOME_POSITION_MIN_LEN, MAVLINK_MSG_ID_HOME_POSITION_LEN, MAVLINK_MSG_ID_HOME_POSITION_CRC); -#else - mavlink_home_position_t packet; - packet.latitude = latitude; - packet.longitude = longitude; - packet.altitude = altitude; - packet.x = x; - packet.y = y; - packet.z = z; - packet.approach_x = approach_x; - packet.approach_y = approach_y; - packet.approach_z = approach_z; - packet.time_usec = time_usec; - mav_array_memcpy(packet.q, q, sizeof(float)*4); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HOME_POSITION, (const char *)&packet, MAVLINK_MSG_ID_HOME_POSITION_MIN_LEN, MAVLINK_MSG_ID_HOME_POSITION_LEN, MAVLINK_MSG_ID_HOME_POSITION_CRC); -#endif -} - -/** - * @brief Send a home_position message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_home_position_send_struct(mavlink_channel_t chan, const mavlink_home_position_t* home_position) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_home_position_send(chan, home_position->latitude, home_position->longitude, home_position->altitude, home_position->x, home_position->y, home_position->z, home_position->q, home_position->approach_x, home_position->approach_y, home_position->approach_z, home_position->time_usec); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HOME_POSITION, (const char *)home_position, MAVLINK_MSG_ID_HOME_POSITION_MIN_LEN, MAVLINK_MSG_ID_HOME_POSITION_LEN, MAVLINK_MSG_ID_HOME_POSITION_CRC); -#endif -} - -#if MAVLINK_MSG_ID_HOME_POSITION_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_home_position_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, int32_t latitude, int32_t longitude, int32_t altitude, float x, float y, float z, const float *q, float approach_x, float approach_y, float approach_z, uint64_t time_usec) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_int32_t(buf, 0, latitude); - _mav_put_int32_t(buf, 4, longitude); - _mav_put_int32_t(buf, 8, altitude); - _mav_put_float(buf, 12, x); - _mav_put_float(buf, 16, y); - _mav_put_float(buf, 20, z); - _mav_put_float(buf, 40, approach_x); - _mav_put_float(buf, 44, approach_y); - _mav_put_float(buf, 48, approach_z); - _mav_put_uint64_t(buf, 52, time_usec); - _mav_put_float_array(buf, 24, q, 4); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HOME_POSITION, buf, MAVLINK_MSG_ID_HOME_POSITION_MIN_LEN, MAVLINK_MSG_ID_HOME_POSITION_LEN, MAVLINK_MSG_ID_HOME_POSITION_CRC); -#else - mavlink_home_position_t *packet = (mavlink_home_position_t *)msgbuf; - packet->latitude = latitude; - packet->longitude = longitude; - packet->altitude = altitude; - packet->x = x; - packet->y = y; - packet->z = z; - packet->approach_x = approach_x; - packet->approach_y = approach_y; - packet->approach_z = approach_z; - packet->time_usec = time_usec; - mav_array_memcpy(packet->q, q, sizeof(float)*4); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HOME_POSITION, (const char *)packet, MAVLINK_MSG_ID_HOME_POSITION_MIN_LEN, MAVLINK_MSG_ID_HOME_POSITION_LEN, MAVLINK_MSG_ID_HOME_POSITION_CRC); -#endif -} -#endif - -#endif - -// MESSAGE HOME_POSITION UNPACKING - - -/** - * @brief Get field latitude from home_position message - * - * @return [degE7] Latitude (WGS84) - */ -static inline int32_t mavlink_msg_home_position_get_latitude(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 0); -} - -/** - * @brief Get field longitude from home_position message - * - * @return [degE7] Longitude (WGS84) - */ -static inline int32_t mavlink_msg_home_position_get_longitude(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 4); -} - -/** - * @brief Get field altitude from home_position message - * - * @return [mm] Altitude (MSL). Positive for up. - */ -static inline int32_t mavlink_msg_home_position_get_altitude(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 8); -} - -/** - * @brief Get field x from home_position message - * - * @return [m] Local X position of this position in the local coordinate frame (NED) - */ -static inline float mavlink_msg_home_position_get_x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field y from home_position message - * - * @return [m] Local Y position of this position in the local coordinate frame (NED) - */ -static inline float mavlink_msg_home_position_get_y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field z from home_position message - * - * @return [m] Local Z position of this position in the local coordinate frame (NED: positive "down") - */ -static inline float mavlink_msg_home_position_get_z(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Get field q from home_position message - * - * @return - Quaternion indicating world-to-surface-normal and heading transformation of the takeoff position. - Used to indicate the heading and slope of the ground. - All fields should be set to NaN if an accurate quaternion for both heading and surface slope cannot be supplied. - - */ -static inline uint16_t mavlink_msg_home_position_get_q(const mavlink_message_t* msg, float *q) -{ - return _MAV_RETURN_float_array(msg, q, 4, 24); -} - -/** - * @brief Get field approach_x from home_position message - * - * @return [m] Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. - */ -static inline float mavlink_msg_home_position_get_approach_x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 40); -} - -/** - * @brief Get field approach_y from home_position message - * - * @return [m] Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. - */ -static inline float mavlink_msg_home_position_get_approach_y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 44); -} - -/** - * @brief Get field approach_z from home_position message - * - * @return [m] Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. - */ -static inline float mavlink_msg_home_position_get_approach_z(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 48); -} - -/** - * @brief Get field time_usec from home_position message - * - * @return [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - */ -static inline uint64_t mavlink_msg_home_position_get_time_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 52); -} - -/** - * @brief Decode a home_position message into a struct - * - * @param msg The message to decode - * @param home_position C-struct to decode the message contents into - */ -static inline void mavlink_msg_home_position_decode(const mavlink_message_t* msg, mavlink_home_position_t* home_position) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - home_position->latitude = mavlink_msg_home_position_get_latitude(msg); - home_position->longitude = mavlink_msg_home_position_get_longitude(msg); - home_position->altitude = mavlink_msg_home_position_get_altitude(msg); - home_position->x = mavlink_msg_home_position_get_x(msg); - home_position->y = mavlink_msg_home_position_get_y(msg); - home_position->z = mavlink_msg_home_position_get_z(msg); - mavlink_msg_home_position_get_q(msg, home_position->q); - home_position->approach_x = mavlink_msg_home_position_get_approach_x(msg); - home_position->approach_y = mavlink_msg_home_position_get_approach_y(msg); - home_position->approach_z = mavlink_msg_home_position_get_approach_z(msg); - home_position->time_usec = mavlink_msg_home_position_get_time_usec(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_HOME_POSITION_LEN? msg->len : MAVLINK_MSG_ID_HOME_POSITION_LEN; - memset(home_position, 0, MAVLINK_MSG_ID_HOME_POSITION_LEN); - memcpy(home_position, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_hygrometer_sensor.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_hygrometer_sensor.h deleted file mode 100644 index 0ae784ff..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_hygrometer_sensor.h +++ /dev/null @@ -1,263 +0,0 @@ -#pragma once -// MESSAGE HYGROMETER_SENSOR PACKING - -#define MAVLINK_MSG_ID_HYGROMETER_SENSOR 12920 - - -typedef struct __mavlink_hygrometer_sensor_t { - int16_t temperature; /*< [cdegC] Temperature*/ - uint16_t humidity; /*< [c%] Humidity*/ - uint8_t id; /*< Hygrometer ID*/ -} mavlink_hygrometer_sensor_t; - -#define MAVLINK_MSG_ID_HYGROMETER_SENSOR_LEN 5 -#define MAVLINK_MSG_ID_HYGROMETER_SENSOR_MIN_LEN 5 -#define MAVLINK_MSG_ID_12920_LEN 5 -#define MAVLINK_MSG_ID_12920_MIN_LEN 5 - -#define MAVLINK_MSG_ID_HYGROMETER_SENSOR_CRC 20 -#define MAVLINK_MSG_ID_12920_CRC 20 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_HYGROMETER_SENSOR { \ - 12920, \ - "HYGROMETER_SENSOR", \ - 3, \ - { { "id", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_hygrometer_sensor_t, id) }, \ - { "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 0, offsetof(mavlink_hygrometer_sensor_t, temperature) }, \ - { "humidity", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_hygrometer_sensor_t, humidity) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_HYGROMETER_SENSOR { \ - "HYGROMETER_SENSOR", \ - 3, \ - { { "id", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_hygrometer_sensor_t, id) }, \ - { "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 0, offsetof(mavlink_hygrometer_sensor_t, temperature) }, \ - { "humidity", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_hygrometer_sensor_t, humidity) }, \ - } \ -} -#endif - -/** - * @brief Pack a hygrometer_sensor message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param id Hygrometer ID - * @param temperature [cdegC] Temperature - * @param humidity [c%] Humidity - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_hygrometer_sensor_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t id, int16_t temperature, uint16_t humidity) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_HYGROMETER_SENSOR_LEN]; - _mav_put_int16_t(buf, 0, temperature); - _mav_put_uint16_t(buf, 2, humidity); - _mav_put_uint8_t(buf, 4, id); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HYGROMETER_SENSOR_LEN); -#else - mavlink_hygrometer_sensor_t packet; - packet.temperature = temperature; - packet.humidity = humidity; - packet.id = id; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HYGROMETER_SENSOR_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_HYGROMETER_SENSOR; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HYGROMETER_SENSOR_MIN_LEN, MAVLINK_MSG_ID_HYGROMETER_SENSOR_LEN, MAVLINK_MSG_ID_HYGROMETER_SENSOR_CRC); -} - -/** - * @brief Pack a hygrometer_sensor message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param id Hygrometer ID - * @param temperature [cdegC] Temperature - * @param humidity [c%] Humidity - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_hygrometer_sensor_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t id,int16_t temperature,uint16_t humidity) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_HYGROMETER_SENSOR_LEN]; - _mav_put_int16_t(buf, 0, temperature); - _mav_put_uint16_t(buf, 2, humidity); - _mav_put_uint8_t(buf, 4, id); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HYGROMETER_SENSOR_LEN); -#else - mavlink_hygrometer_sensor_t packet; - packet.temperature = temperature; - packet.humidity = humidity; - packet.id = id; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HYGROMETER_SENSOR_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_HYGROMETER_SENSOR; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HYGROMETER_SENSOR_MIN_LEN, MAVLINK_MSG_ID_HYGROMETER_SENSOR_LEN, MAVLINK_MSG_ID_HYGROMETER_SENSOR_CRC); -} - -/** - * @brief Encode a hygrometer_sensor struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param hygrometer_sensor C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_hygrometer_sensor_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_hygrometer_sensor_t* hygrometer_sensor) -{ - return mavlink_msg_hygrometer_sensor_pack(system_id, component_id, msg, hygrometer_sensor->id, hygrometer_sensor->temperature, hygrometer_sensor->humidity); -} - -/** - * @brief Encode a hygrometer_sensor struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param hygrometer_sensor C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_hygrometer_sensor_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_hygrometer_sensor_t* hygrometer_sensor) -{ - return mavlink_msg_hygrometer_sensor_pack_chan(system_id, component_id, chan, msg, hygrometer_sensor->id, hygrometer_sensor->temperature, hygrometer_sensor->humidity); -} - -/** - * @brief Send a hygrometer_sensor message - * @param chan MAVLink channel to send the message - * - * @param id Hygrometer ID - * @param temperature [cdegC] Temperature - * @param humidity [c%] Humidity - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_hygrometer_sensor_send(mavlink_channel_t chan, uint8_t id, int16_t temperature, uint16_t humidity) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_HYGROMETER_SENSOR_LEN]; - _mav_put_int16_t(buf, 0, temperature); - _mav_put_uint16_t(buf, 2, humidity); - _mav_put_uint8_t(buf, 4, id); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HYGROMETER_SENSOR, buf, MAVLINK_MSG_ID_HYGROMETER_SENSOR_MIN_LEN, MAVLINK_MSG_ID_HYGROMETER_SENSOR_LEN, MAVLINK_MSG_ID_HYGROMETER_SENSOR_CRC); -#else - mavlink_hygrometer_sensor_t packet; - packet.temperature = temperature; - packet.humidity = humidity; - packet.id = id; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HYGROMETER_SENSOR, (const char *)&packet, MAVLINK_MSG_ID_HYGROMETER_SENSOR_MIN_LEN, MAVLINK_MSG_ID_HYGROMETER_SENSOR_LEN, MAVLINK_MSG_ID_HYGROMETER_SENSOR_CRC); -#endif -} - -/** - * @brief Send a hygrometer_sensor message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_hygrometer_sensor_send_struct(mavlink_channel_t chan, const mavlink_hygrometer_sensor_t* hygrometer_sensor) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_hygrometer_sensor_send(chan, hygrometer_sensor->id, hygrometer_sensor->temperature, hygrometer_sensor->humidity); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HYGROMETER_SENSOR, (const char *)hygrometer_sensor, MAVLINK_MSG_ID_HYGROMETER_SENSOR_MIN_LEN, MAVLINK_MSG_ID_HYGROMETER_SENSOR_LEN, MAVLINK_MSG_ID_HYGROMETER_SENSOR_CRC); -#endif -} - -#if MAVLINK_MSG_ID_HYGROMETER_SENSOR_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_hygrometer_sensor_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t id, int16_t temperature, uint16_t humidity) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_int16_t(buf, 0, temperature); - _mav_put_uint16_t(buf, 2, humidity); - _mav_put_uint8_t(buf, 4, id); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HYGROMETER_SENSOR, buf, MAVLINK_MSG_ID_HYGROMETER_SENSOR_MIN_LEN, MAVLINK_MSG_ID_HYGROMETER_SENSOR_LEN, MAVLINK_MSG_ID_HYGROMETER_SENSOR_CRC); -#else - mavlink_hygrometer_sensor_t *packet = (mavlink_hygrometer_sensor_t *)msgbuf; - packet->temperature = temperature; - packet->humidity = humidity; - packet->id = id; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HYGROMETER_SENSOR, (const char *)packet, MAVLINK_MSG_ID_HYGROMETER_SENSOR_MIN_LEN, MAVLINK_MSG_ID_HYGROMETER_SENSOR_LEN, MAVLINK_MSG_ID_HYGROMETER_SENSOR_CRC); -#endif -} -#endif - -#endif - -// MESSAGE HYGROMETER_SENSOR UNPACKING - - -/** - * @brief Get field id from hygrometer_sensor message - * - * @return Hygrometer ID - */ -static inline uint8_t mavlink_msg_hygrometer_sensor_get_id(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 4); -} - -/** - * @brief Get field temperature from hygrometer_sensor message - * - * @return [cdegC] Temperature - */ -static inline int16_t mavlink_msg_hygrometer_sensor_get_temperature(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 0); -} - -/** - * @brief Get field humidity from hygrometer_sensor message - * - * @return [c%] Humidity - */ -static inline uint16_t mavlink_msg_hygrometer_sensor_get_humidity(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 2); -} - -/** - * @brief Decode a hygrometer_sensor message into a struct - * - * @param msg The message to decode - * @param hygrometer_sensor C-struct to decode the message contents into - */ -static inline void mavlink_msg_hygrometer_sensor_decode(const mavlink_message_t* msg, mavlink_hygrometer_sensor_t* hygrometer_sensor) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - hygrometer_sensor->temperature = mavlink_msg_hygrometer_sensor_get_temperature(msg); - hygrometer_sensor->humidity = mavlink_msg_hygrometer_sensor_get_humidity(msg); - hygrometer_sensor->id = mavlink_msg_hygrometer_sensor_get_id(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_HYGROMETER_SENSOR_LEN? msg->len : MAVLINK_MSG_ID_HYGROMETER_SENSOR_LEN; - memset(hygrometer_sensor, 0, MAVLINK_MSG_ID_HYGROMETER_SENSOR_LEN); - memcpy(hygrometer_sensor, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_isbd_link_status.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_isbd_link_status.h deleted file mode 100644 index 7273e11a..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_isbd_link_status.h +++ /dev/null @@ -1,388 +0,0 @@ -#pragma once -// MESSAGE ISBD_LINK_STATUS PACKING - -#define MAVLINK_MSG_ID_ISBD_LINK_STATUS 335 - - -typedef struct __mavlink_isbd_link_status_t { - uint64_t timestamp; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/ - uint64_t last_heartbeat; /*< [us] Timestamp of the last successful sbd session. The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/ - uint16_t failed_sessions; /*< Number of failed SBD sessions.*/ - uint16_t successful_sessions; /*< Number of successful SBD sessions.*/ - uint8_t signal_quality; /*< Signal quality equal to the number of bars displayed on the ISU signal strength indicator. Range is 0 to 5, where 0 indicates no signal and 5 indicates maximum signal strength.*/ - uint8_t ring_pending; /*< 1: Ring call pending, 0: No call pending.*/ - uint8_t tx_session_pending; /*< 1: Transmission session pending, 0: No transmission session pending.*/ - uint8_t rx_session_pending; /*< 1: Receiving session pending, 0: No receiving session pending.*/ -} mavlink_isbd_link_status_t; - -#define MAVLINK_MSG_ID_ISBD_LINK_STATUS_LEN 24 -#define MAVLINK_MSG_ID_ISBD_LINK_STATUS_MIN_LEN 24 -#define MAVLINK_MSG_ID_335_LEN 24 -#define MAVLINK_MSG_ID_335_MIN_LEN 24 - -#define MAVLINK_MSG_ID_ISBD_LINK_STATUS_CRC 225 -#define MAVLINK_MSG_ID_335_CRC 225 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_ISBD_LINK_STATUS { \ - 335, \ - "ISBD_LINK_STATUS", \ - 8, \ - { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_isbd_link_status_t, timestamp) }, \ - { "last_heartbeat", NULL, MAVLINK_TYPE_UINT64_T, 0, 8, offsetof(mavlink_isbd_link_status_t, last_heartbeat) }, \ - { "failed_sessions", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_isbd_link_status_t, failed_sessions) }, \ - { "successful_sessions", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_isbd_link_status_t, successful_sessions) }, \ - { "signal_quality", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_isbd_link_status_t, signal_quality) }, \ - { "ring_pending", NULL, MAVLINK_TYPE_UINT8_T, 0, 21, offsetof(mavlink_isbd_link_status_t, ring_pending) }, \ - { "tx_session_pending", NULL, MAVLINK_TYPE_UINT8_T, 0, 22, offsetof(mavlink_isbd_link_status_t, tx_session_pending) }, \ - { "rx_session_pending", NULL, MAVLINK_TYPE_UINT8_T, 0, 23, offsetof(mavlink_isbd_link_status_t, rx_session_pending) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_ISBD_LINK_STATUS { \ - "ISBD_LINK_STATUS", \ - 8, \ - { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_isbd_link_status_t, timestamp) }, \ - { "last_heartbeat", NULL, MAVLINK_TYPE_UINT64_T, 0, 8, offsetof(mavlink_isbd_link_status_t, last_heartbeat) }, \ - { "failed_sessions", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_isbd_link_status_t, failed_sessions) }, \ - { "successful_sessions", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_isbd_link_status_t, successful_sessions) }, \ - { "signal_quality", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_isbd_link_status_t, signal_quality) }, \ - { "ring_pending", NULL, MAVLINK_TYPE_UINT8_T, 0, 21, offsetof(mavlink_isbd_link_status_t, ring_pending) }, \ - { "tx_session_pending", NULL, MAVLINK_TYPE_UINT8_T, 0, 22, offsetof(mavlink_isbd_link_status_t, tx_session_pending) }, \ - { "rx_session_pending", NULL, MAVLINK_TYPE_UINT8_T, 0, 23, offsetof(mavlink_isbd_link_status_t, rx_session_pending) }, \ - } \ -} -#endif - -/** - * @brief Pack a isbd_link_status message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param timestamp [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @param last_heartbeat [us] Timestamp of the last successful sbd session. The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @param failed_sessions Number of failed SBD sessions. - * @param successful_sessions Number of successful SBD sessions. - * @param signal_quality Signal quality equal to the number of bars displayed on the ISU signal strength indicator. Range is 0 to 5, where 0 indicates no signal and 5 indicates maximum signal strength. - * @param ring_pending 1: Ring call pending, 0: No call pending. - * @param tx_session_pending 1: Transmission session pending, 0: No transmission session pending. - * @param rx_session_pending 1: Receiving session pending, 0: No receiving session pending. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_isbd_link_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint64_t timestamp, uint64_t last_heartbeat, uint16_t failed_sessions, uint16_t successful_sessions, uint8_t signal_quality, uint8_t ring_pending, uint8_t tx_session_pending, uint8_t rx_session_pending) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_ISBD_LINK_STATUS_LEN]; - _mav_put_uint64_t(buf, 0, timestamp); - _mav_put_uint64_t(buf, 8, last_heartbeat); - _mav_put_uint16_t(buf, 16, failed_sessions); - _mav_put_uint16_t(buf, 18, successful_sessions); - _mav_put_uint8_t(buf, 20, signal_quality); - _mav_put_uint8_t(buf, 21, ring_pending); - _mav_put_uint8_t(buf, 22, tx_session_pending); - _mav_put_uint8_t(buf, 23, rx_session_pending); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ISBD_LINK_STATUS_LEN); -#else - mavlink_isbd_link_status_t packet; - packet.timestamp = timestamp; - packet.last_heartbeat = last_heartbeat; - packet.failed_sessions = failed_sessions; - packet.successful_sessions = successful_sessions; - packet.signal_quality = signal_quality; - packet.ring_pending = ring_pending; - packet.tx_session_pending = tx_session_pending; - packet.rx_session_pending = rx_session_pending; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ISBD_LINK_STATUS_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_ISBD_LINK_STATUS; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ISBD_LINK_STATUS_MIN_LEN, MAVLINK_MSG_ID_ISBD_LINK_STATUS_LEN, MAVLINK_MSG_ID_ISBD_LINK_STATUS_CRC); -} - -/** - * @brief Pack a isbd_link_status message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param timestamp [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @param last_heartbeat [us] Timestamp of the last successful sbd session. The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @param failed_sessions Number of failed SBD sessions. - * @param successful_sessions Number of successful SBD sessions. - * @param signal_quality Signal quality equal to the number of bars displayed on the ISU signal strength indicator. Range is 0 to 5, where 0 indicates no signal and 5 indicates maximum signal strength. - * @param ring_pending 1: Ring call pending, 0: No call pending. - * @param tx_session_pending 1: Transmission session pending, 0: No transmission session pending. - * @param rx_session_pending 1: Receiving session pending, 0: No receiving session pending. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_isbd_link_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint64_t timestamp,uint64_t last_heartbeat,uint16_t failed_sessions,uint16_t successful_sessions,uint8_t signal_quality,uint8_t ring_pending,uint8_t tx_session_pending,uint8_t rx_session_pending) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_ISBD_LINK_STATUS_LEN]; - _mav_put_uint64_t(buf, 0, timestamp); - _mav_put_uint64_t(buf, 8, last_heartbeat); - _mav_put_uint16_t(buf, 16, failed_sessions); - _mav_put_uint16_t(buf, 18, successful_sessions); - _mav_put_uint8_t(buf, 20, signal_quality); - _mav_put_uint8_t(buf, 21, ring_pending); - _mav_put_uint8_t(buf, 22, tx_session_pending); - _mav_put_uint8_t(buf, 23, rx_session_pending); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ISBD_LINK_STATUS_LEN); -#else - mavlink_isbd_link_status_t packet; - packet.timestamp = timestamp; - packet.last_heartbeat = last_heartbeat; - packet.failed_sessions = failed_sessions; - packet.successful_sessions = successful_sessions; - packet.signal_quality = signal_quality; - packet.ring_pending = ring_pending; - packet.tx_session_pending = tx_session_pending; - packet.rx_session_pending = rx_session_pending; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ISBD_LINK_STATUS_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_ISBD_LINK_STATUS; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ISBD_LINK_STATUS_MIN_LEN, MAVLINK_MSG_ID_ISBD_LINK_STATUS_LEN, MAVLINK_MSG_ID_ISBD_LINK_STATUS_CRC); -} - -/** - * @brief Encode a isbd_link_status struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param isbd_link_status C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_isbd_link_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_isbd_link_status_t* isbd_link_status) -{ - return mavlink_msg_isbd_link_status_pack(system_id, component_id, msg, isbd_link_status->timestamp, isbd_link_status->last_heartbeat, isbd_link_status->failed_sessions, isbd_link_status->successful_sessions, isbd_link_status->signal_quality, isbd_link_status->ring_pending, isbd_link_status->tx_session_pending, isbd_link_status->rx_session_pending); -} - -/** - * @brief Encode a isbd_link_status struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param isbd_link_status C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_isbd_link_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_isbd_link_status_t* isbd_link_status) -{ - return mavlink_msg_isbd_link_status_pack_chan(system_id, component_id, chan, msg, isbd_link_status->timestamp, isbd_link_status->last_heartbeat, isbd_link_status->failed_sessions, isbd_link_status->successful_sessions, isbd_link_status->signal_quality, isbd_link_status->ring_pending, isbd_link_status->tx_session_pending, isbd_link_status->rx_session_pending); -} - -/** - * @brief Send a isbd_link_status message - * @param chan MAVLink channel to send the message - * - * @param timestamp [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @param last_heartbeat [us] Timestamp of the last successful sbd session. The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @param failed_sessions Number of failed SBD sessions. - * @param successful_sessions Number of successful SBD sessions. - * @param signal_quality Signal quality equal to the number of bars displayed on the ISU signal strength indicator. Range is 0 to 5, where 0 indicates no signal and 5 indicates maximum signal strength. - * @param ring_pending 1: Ring call pending, 0: No call pending. - * @param tx_session_pending 1: Transmission session pending, 0: No transmission session pending. - * @param rx_session_pending 1: Receiving session pending, 0: No receiving session pending. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_isbd_link_status_send(mavlink_channel_t chan, uint64_t timestamp, uint64_t last_heartbeat, uint16_t failed_sessions, uint16_t successful_sessions, uint8_t signal_quality, uint8_t ring_pending, uint8_t tx_session_pending, uint8_t rx_session_pending) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_ISBD_LINK_STATUS_LEN]; - _mav_put_uint64_t(buf, 0, timestamp); - _mav_put_uint64_t(buf, 8, last_heartbeat); - _mav_put_uint16_t(buf, 16, failed_sessions); - _mav_put_uint16_t(buf, 18, successful_sessions); - _mav_put_uint8_t(buf, 20, signal_quality); - _mav_put_uint8_t(buf, 21, ring_pending); - _mav_put_uint8_t(buf, 22, tx_session_pending); - _mav_put_uint8_t(buf, 23, rx_session_pending); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ISBD_LINK_STATUS, buf, MAVLINK_MSG_ID_ISBD_LINK_STATUS_MIN_LEN, MAVLINK_MSG_ID_ISBD_LINK_STATUS_LEN, MAVLINK_MSG_ID_ISBD_LINK_STATUS_CRC); -#else - mavlink_isbd_link_status_t packet; - packet.timestamp = timestamp; - packet.last_heartbeat = last_heartbeat; - packet.failed_sessions = failed_sessions; - packet.successful_sessions = successful_sessions; - packet.signal_quality = signal_quality; - packet.ring_pending = ring_pending; - packet.tx_session_pending = tx_session_pending; - packet.rx_session_pending = rx_session_pending; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ISBD_LINK_STATUS, (const char *)&packet, MAVLINK_MSG_ID_ISBD_LINK_STATUS_MIN_LEN, MAVLINK_MSG_ID_ISBD_LINK_STATUS_LEN, MAVLINK_MSG_ID_ISBD_LINK_STATUS_CRC); -#endif -} - -/** - * @brief Send a isbd_link_status message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_isbd_link_status_send_struct(mavlink_channel_t chan, const mavlink_isbd_link_status_t* isbd_link_status) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_isbd_link_status_send(chan, isbd_link_status->timestamp, isbd_link_status->last_heartbeat, isbd_link_status->failed_sessions, isbd_link_status->successful_sessions, isbd_link_status->signal_quality, isbd_link_status->ring_pending, isbd_link_status->tx_session_pending, isbd_link_status->rx_session_pending); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ISBD_LINK_STATUS, (const char *)isbd_link_status, MAVLINK_MSG_ID_ISBD_LINK_STATUS_MIN_LEN, MAVLINK_MSG_ID_ISBD_LINK_STATUS_LEN, MAVLINK_MSG_ID_ISBD_LINK_STATUS_CRC); -#endif -} - -#if MAVLINK_MSG_ID_ISBD_LINK_STATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_isbd_link_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp, uint64_t last_heartbeat, uint16_t failed_sessions, uint16_t successful_sessions, uint8_t signal_quality, uint8_t ring_pending, uint8_t tx_session_pending, uint8_t rx_session_pending) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, timestamp); - _mav_put_uint64_t(buf, 8, last_heartbeat); - _mav_put_uint16_t(buf, 16, failed_sessions); - _mav_put_uint16_t(buf, 18, successful_sessions); - _mav_put_uint8_t(buf, 20, signal_quality); - _mav_put_uint8_t(buf, 21, ring_pending); - _mav_put_uint8_t(buf, 22, tx_session_pending); - _mav_put_uint8_t(buf, 23, rx_session_pending); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ISBD_LINK_STATUS, buf, MAVLINK_MSG_ID_ISBD_LINK_STATUS_MIN_LEN, MAVLINK_MSG_ID_ISBD_LINK_STATUS_LEN, MAVLINK_MSG_ID_ISBD_LINK_STATUS_CRC); -#else - mavlink_isbd_link_status_t *packet = (mavlink_isbd_link_status_t *)msgbuf; - packet->timestamp = timestamp; - packet->last_heartbeat = last_heartbeat; - packet->failed_sessions = failed_sessions; - packet->successful_sessions = successful_sessions; - packet->signal_quality = signal_quality; - packet->ring_pending = ring_pending; - packet->tx_session_pending = tx_session_pending; - packet->rx_session_pending = rx_session_pending; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ISBD_LINK_STATUS, (const char *)packet, MAVLINK_MSG_ID_ISBD_LINK_STATUS_MIN_LEN, MAVLINK_MSG_ID_ISBD_LINK_STATUS_LEN, MAVLINK_MSG_ID_ISBD_LINK_STATUS_CRC); -#endif -} -#endif - -#endif - -// MESSAGE ISBD_LINK_STATUS UNPACKING - - -/** - * @brief Get field timestamp from isbd_link_status message - * - * @return [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - */ -static inline uint64_t mavlink_msg_isbd_link_status_get_timestamp(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field last_heartbeat from isbd_link_status message - * - * @return [us] Timestamp of the last successful sbd session. The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - */ -static inline uint64_t mavlink_msg_isbd_link_status_get_last_heartbeat(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 8); -} - -/** - * @brief Get field failed_sessions from isbd_link_status message - * - * @return Number of failed SBD sessions. - */ -static inline uint16_t mavlink_msg_isbd_link_status_get_failed_sessions(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 16); -} - -/** - * @brief Get field successful_sessions from isbd_link_status message - * - * @return Number of successful SBD sessions. - */ -static inline uint16_t mavlink_msg_isbd_link_status_get_successful_sessions(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 18); -} - -/** - * @brief Get field signal_quality from isbd_link_status message - * - * @return Signal quality equal to the number of bars displayed on the ISU signal strength indicator. Range is 0 to 5, where 0 indicates no signal and 5 indicates maximum signal strength. - */ -static inline uint8_t mavlink_msg_isbd_link_status_get_signal_quality(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 20); -} - -/** - * @brief Get field ring_pending from isbd_link_status message - * - * @return 1: Ring call pending, 0: No call pending. - */ -static inline uint8_t mavlink_msg_isbd_link_status_get_ring_pending(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 21); -} - -/** - * @brief Get field tx_session_pending from isbd_link_status message - * - * @return 1: Transmission session pending, 0: No transmission session pending. - */ -static inline uint8_t mavlink_msg_isbd_link_status_get_tx_session_pending(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 22); -} - -/** - * @brief Get field rx_session_pending from isbd_link_status message - * - * @return 1: Receiving session pending, 0: No receiving session pending. - */ -static inline uint8_t mavlink_msg_isbd_link_status_get_rx_session_pending(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 23); -} - -/** - * @brief Decode a isbd_link_status message into a struct - * - * @param msg The message to decode - * @param isbd_link_status C-struct to decode the message contents into - */ -static inline void mavlink_msg_isbd_link_status_decode(const mavlink_message_t* msg, mavlink_isbd_link_status_t* isbd_link_status) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - isbd_link_status->timestamp = mavlink_msg_isbd_link_status_get_timestamp(msg); - isbd_link_status->last_heartbeat = mavlink_msg_isbd_link_status_get_last_heartbeat(msg); - isbd_link_status->failed_sessions = mavlink_msg_isbd_link_status_get_failed_sessions(msg); - isbd_link_status->successful_sessions = mavlink_msg_isbd_link_status_get_successful_sessions(msg); - isbd_link_status->signal_quality = mavlink_msg_isbd_link_status_get_signal_quality(msg); - isbd_link_status->ring_pending = mavlink_msg_isbd_link_status_get_ring_pending(msg); - isbd_link_status->tx_session_pending = mavlink_msg_isbd_link_status_get_tx_session_pending(msg); - isbd_link_status->rx_session_pending = mavlink_msg_isbd_link_status_get_rx_session_pending(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_ISBD_LINK_STATUS_LEN? msg->len : MAVLINK_MSG_ID_ISBD_LINK_STATUS_LEN; - memset(isbd_link_status, 0, MAVLINK_MSG_ID_ISBD_LINK_STATUS_LEN); - memcpy(isbd_link_status, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_landing_target.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_landing_target.h deleted file mode 100644 index 1de2d9ef..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_landing_target.h +++ /dev/null @@ -1,530 +0,0 @@ -#pragma once -// MESSAGE LANDING_TARGET PACKING - -#define MAVLINK_MSG_ID_LANDING_TARGET 149 - -MAVPACKED( -typedef struct __mavlink_landing_target_t { - uint64_t time_usec; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/ - float angle_x; /*< [rad] X-axis angular offset of the target from the center of the image*/ - float angle_y; /*< [rad] Y-axis angular offset of the target from the center of the image*/ - float distance; /*< [m] Distance to the target from the vehicle*/ - float size_x; /*< [rad] Size of target along x-axis*/ - float size_y; /*< [rad] Size of target along y-axis*/ - uint8_t target_num; /*< The ID of the target if multiple targets are present*/ - uint8_t frame; /*< Coordinate frame used for following fields.*/ - float x; /*< [m] X Position of the landing target in MAV_FRAME*/ - float y; /*< [m] Y Position of the landing target in MAV_FRAME*/ - float z; /*< [m] Z Position of the landing target in MAV_FRAME*/ - float q[4]; /*< Quaternion of landing target orientation (w, x, y, z order, zero-rotation is 1, 0, 0, 0)*/ - uint8_t type; /*< Type of landing target*/ - uint8_t position_valid; /*< Boolean indicating whether the position fields (x, y, z, q, type) contain valid target position information (valid: 1, invalid: 0). Default is 0 (invalid).*/ -}) mavlink_landing_target_t; - -#define MAVLINK_MSG_ID_LANDING_TARGET_LEN 60 -#define MAVLINK_MSG_ID_LANDING_TARGET_MIN_LEN 30 -#define MAVLINK_MSG_ID_149_LEN 60 -#define MAVLINK_MSG_ID_149_MIN_LEN 30 - -#define MAVLINK_MSG_ID_LANDING_TARGET_CRC 200 -#define MAVLINK_MSG_ID_149_CRC 200 - -#define MAVLINK_MSG_LANDING_TARGET_FIELD_Q_LEN 4 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_LANDING_TARGET { \ - 149, \ - "LANDING_TARGET", \ - 14, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_landing_target_t, time_usec) }, \ - { "target_num", NULL, MAVLINK_TYPE_UINT8_T, 0, 28, offsetof(mavlink_landing_target_t, target_num) }, \ - { "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 29, offsetof(mavlink_landing_target_t, frame) }, \ - { "angle_x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_landing_target_t, angle_x) }, \ - { "angle_y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_landing_target_t, angle_y) }, \ - { "distance", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_landing_target_t, distance) }, \ - { "size_x", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_landing_target_t, size_x) }, \ - { "size_y", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_landing_target_t, size_y) }, \ - { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 30, offsetof(mavlink_landing_target_t, x) }, \ - { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 34, offsetof(mavlink_landing_target_t, y) }, \ - { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 38, offsetof(mavlink_landing_target_t, z) }, \ - { "q", NULL, MAVLINK_TYPE_FLOAT, 4, 42, offsetof(mavlink_landing_target_t, q) }, \ - { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 58, offsetof(mavlink_landing_target_t, type) }, \ - { "position_valid", NULL, MAVLINK_TYPE_UINT8_T, 0, 59, offsetof(mavlink_landing_target_t, position_valid) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_LANDING_TARGET { \ - "LANDING_TARGET", \ - 14, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_landing_target_t, time_usec) }, \ - { "target_num", NULL, MAVLINK_TYPE_UINT8_T, 0, 28, offsetof(mavlink_landing_target_t, target_num) }, \ - { "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 29, offsetof(mavlink_landing_target_t, frame) }, \ - { "angle_x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_landing_target_t, angle_x) }, \ - { "angle_y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_landing_target_t, angle_y) }, \ - { "distance", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_landing_target_t, distance) }, \ - { "size_x", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_landing_target_t, size_x) }, \ - { "size_y", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_landing_target_t, size_y) }, \ - { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 30, offsetof(mavlink_landing_target_t, x) }, \ - { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 34, offsetof(mavlink_landing_target_t, y) }, \ - { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 38, offsetof(mavlink_landing_target_t, z) }, \ - { "q", NULL, MAVLINK_TYPE_FLOAT, 4, 42, offsetof(mavlink_landing_target_t, q) }, \ - { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 58, offsetof(mavlink_landing_target_t, type) }, \ - { "position_valid", NULL, MAVLINK_TYPE_UINT8_T, 0, 59, offsetof(mavlink_landing_target_t, position_valid) }, \ - } \ -} -#endif - -/** - * @brief Pack a landing_target message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @param target_num The ID of the target if multiple targets are present - * @param frame Coordinate frame used for following fields. - * @param angle_x [rad] X-axis angular offset of the target from the center of the image - * @param angle_y [rad] Y-axis angular offset of the target from the center of the image - * @param distance [m] Distance to the target from the vehicle - * @param size_x [rad] Size of target along x-axis - * @param size_y [rad] Size of target along y-axis - * @param x [m] X Position of the landing target in MAV_FRAME - * @param y [m] Y Position of the landing target in MAV_FRAME - * @param z [m] Z Position of the landing target in MAV_FRAME - * @param q Quaternion of landing target orientation (w, x, y, z order, zero-rotation is 1, 0, 0, 0) - * @param type Type of landing target - * @param position_valid Boolean indicating whether the position fields (x, y, z, q, type) contain valid target position information (valid: 1, invalid: 0). Default is 0 (invalid). - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_landing_target_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint64_t time_usec, uint8_t target_num, uint8_t frame, float angle_x, float angle_y, float distance, float size_x, float size_y, float x, float y, float z, const float *q, uint8_t type, uint8_t position_valid) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LANDING_TARGET_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, angle_x); - _mav_put_float(buf, 12, angle_y); - _mav_put_float(buf, 16, distance); - _mav_put_float(buf, 20, size_x); - _mav_put_float(buf, 24, size_y); - _mav_put_uint8_t(buf, 28, target_num); - _mav_put_uint8_t(buf, 29, frame); - _mav_put_float(buf, 30, x); - _mav_put_float(buf, 34, y); - _mav_put_float(buf, 38, z); - _mav_put_uint8_t(buf, 58, type); - _mav_put_uint8_t(buf, 59, position_valid); - _mav_put_float_array(buf, 42, q, 4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LANDING_TARGET_LEN); -#else - mavlink_landing_target_t packet; - packet.time_usec = time_usec; - packet.angle_x = angle_x; - packet.angle_y = angle_y; - packet.distance = distance; - packet.size_x = size_x; - packet.size_y = size_y; - packet.target_num = target_num; - packet.frame = frame; - packet.x = x; - packet.y = y; - packet.z = z; - packet.type = type; - packet.position_valid = position_valid; - mav_array_memcpy(packet.q, q, sizeof(float)*4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LANDING_TARGET_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_LANDING_TARGET; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LANDING_TARGET_MIN_LEN, MAVLINK_MSG_ID_LANDING_TARGET_LEN, MAVLINK_MSG_ID_LANDING_TARGET_CRC); -} - -/** - * @brief Pack a landing_target message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @param target_num The ID of the target if multiple targets are present - * @param frame Coordinate frame used for following fields. - * @param angle_x [rad] X-axis angular offset of the target from the center of the image - * @param angle_y [rad] Y-axis angular offset of the target from the center of the image - * @param distance [m] Distance to the target from the vehicle - * @param size_x [rad] Size of target along x-axis - * @param size_y [rad] Size of target along y-axis - * @param x [m] X Position of the landing target in MAV_FRAME - * @param y [m] Y Position of the landing target in MAV_FRAME - * @param z [m] Z Position of the landing target in MAV_FRAME - * @param q Quaternion of landing target orientation (w, x, y, z order, zero-rotation is 1, 0, 0, 0) - * @param type Type of landing target - * @param position_valid Boolean indicating whether the position fields (x, y, z, q, type) contain valid target position information (valid: 1, invalid: 0). Default is 0 (invalid). - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_landing_target_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint64_t time_usec,uint8_t target_num,uint8_t frame,float angle_x,float angle_y,float distance,float size_x,float size_y,float x,float y,float z,const float *q,uint8_t type,uint8_t position_valid) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LANDING_TARGET_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, angle_x); - _mav_put_float(buf, 12, angle_y); - _mav_put_float(buf, 16, distance); - _mav_put_float(buf, 20, size_x); - _mav_put_float(buf, 24, size_y); - _mav_put_uint8_t(buf, 28, target_num); - _mav_put_uint8_t(buf, 29, frame); - _mav_put_float(buf, 30, x); - _mav_put_float(buf, 34, y); - _mav_put_float(buf, 38, z); - _mav_put_uint8_t(buf, 58, type); - _mav_put_uint8_t(buf, 59, position_valid); - _mav_put_float_array(buf, 42, q, 4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LANDING_TARGET_LEN); -#else - mavlink_landing_target_t packet; - packet.time_usec = time_usec; - packet.angle_x = angle_x; - packet.angle_y = angle_y; - packet.distance = distance; - packet.size_x = size_x; - packet.size_y = size_y; - packet.target_num = target_num; - packet.frame = frame; - packet.x = x; - packet.y = y; - packet.z = z; - packet.type = type; - packet.position_valid = position_valid; - mav_array_memcpy(packet.q, q, sizeof(float)*4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LANDING_TARGET_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_LANDING_TARGET; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LANDING_TARGET_MIN_LEN, MAVLINK_MSG_ID_LANDING_TARGET_LEN, MAVLINK_MSG_ID_LANDING_TARGET_CRC); -} - -/** - * @brief Encode a landing_target struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param landing_target C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_landing_target_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_landing_target_t* landing_target) -{ - return mavlink_msg_landing_target_pack(system_id, component_id, msg, landing_target->time_usec, landing_target->target_num, landing_target->frame, landing_target->angle_x, landing_target->angle_y, landing_target->distance, landing_target->size_x, landing_target->size_y, landing_target->x, landing_target->y, landing_target->z, landing_target->q, landing_target->type, landing_target->position_valid); -} - -/** - * @brief Encode a landing_target struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param landing_target C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_landing_target_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_landing_target_t* landing_target) -{ - return mavlink_msg_landing_target_pack_chan(system_id, component_id, chan, msg, landing_target->time_usec, landing_target->target_num, landing_target->frame, landing_target->angle_x, landing_target->angle_y, landing_target->distance, landing_target->size_x, landing_target->size_y, landing_target->x, landing_target->y, landing_target->z, landing_target->q, landing_target->type, landing_target->position_valid); -} - -/** - * @brief Send a landing_target message - * @param chan MAVLink channel to send the message - * - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @param target_num The ID of the target if multiple targets are present - * @param frame Coordinate frame used for following fields. - * @param angle_x [rad] X-axis angular offset of the target from the center of the image - * @param angle_y [rad] Y-axis angular offset of the target from the center of the image - * @param distance [m] Distance to the target from the vehicle - * @param size_x [rad] Size of target along x-axis - * @param size_y [rad] Size of target along y-axis - * @param x [m] X Position of the landing target in MAV_FRAME - * @param y [m] Y Position of the landing target in MAV_FRAME - * @param z [m] Z Position of the landing target in MAV_FRAME - * @param q Quaternion of landing target orientation (w, x, y, z order, zero-rotation is 1, 0, 0, 0) - * @param type Type of landing target - * @param position_valid Boolean indicating whether the position fields (x, y, z, q, type) contain valid target position information (valid: 1, invalid: 0). Default is 0 (invalid). - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_landing_target_send(mavlink_channel_t chan, uint64_t time_usec, uint8_t target_num, uint8_t frame, float angle_x, float angle_y, float distance, float size_x, float size_y, float x, float y, float z, const float *q, uint8_t type, uint8_t position_valid) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LANDING_TARGET_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, angle_x); - _mav_put_float(buf, 12, angle_y); - _mav_put_float(buf, 16, distance); - _mav_put_float(buf, 20, size_x); - _mav_put_float(buf, 24, size_y); - _mav_put_uint8_t(buf, 28, target_num); - _mav_put_uint8_t(buf, 29, frame); - _mav_put_float(buf, 30, x); - _mav_put_float(buf, 34, y); - _mav_put_float(buf, 38, z); - _mav_put_uint8_t(buf, 58, type); - _mav_put_uint8_t(buf, 59, position_valid); - _mav_put_float_array(buf, 42, q, 4); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LANDING_TARGET, buf, MAVLINK_MSG_ID_LANDING_TARGET_MIN_LEN, MAVLINK_MSG_ID_LANDING_TARGET_LEN, MAVLINK_MSG_ID_LANDING_TARGET_CRC); -#else - mavlink_landing_target_t packet; - packet.time_usec = time_usec; - packet.angle_x = angle_x; - packet.angle_y = angle_y; - packet.distance = distance; - packet.size_x = size_x; - packet.size_y = size_y; - packet.target_num = target_num; - packet.frame = frame; - packet.x = x; - packet.y = y; - packet.z = z; - packet.type = type; - packet.position_valid = position_valid; - mav_array_memcpy(packet.q, q, sizeof(float)*4); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LANDING_TARGET, (const char *)&packet, MAVLINK_MSG_ID_LANDING_TARGET_MIN_LEN, MAVLINK_MSG_ID_LANDING_TARGET_LEN, MAVLINK_MSG_ID_LANDING_TARGET_CRC); -#endif -} - -/** - * @brief Send a landing_target message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_landing_target_send_struct(mavlink_channel_t chan, const mavlink_landing_target_t* landing_target) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_landing_target_send(chan, landing_target->time_usec, landing_target->target_num, landing_target->frame, landing_target->angle_x, landing_target->angle_y, landing_target->distance, landing_target->size_x, landing_target->size_y, landing_target->x, landing_target->y, landing_target->z, landing_target->q, landing_target->type, landing_target->position_valid); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LANDING_TARGET, (const char *)landing_target, MAVLINK_MSG_ID_LANDING_TARGET_MIN_LEN, MAVLINK_MSG_ID_LANDING_TARGET_LEN, MAVLINK_MSG_ID_LANDING_TARGET_CRC); -#endif -} - -#if MAVLINK_MSG_ID_LANDING_TARGET_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_landing_target_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, uint8_t target_num, uint8_t frame, float angle_x, float angle_y, float distance, float size_x, float size_y, float x, float y, float z, const float *q, uint8_t type, uint8_t position_valid) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, angle_x); - _mav_put_float(buf, 12, angle_y); - _mav_put_float(buf, 16, distance); - _mav_put_float(buf, 20, size_x); - _mav_put_float(buf, 24, size_y); - _mav_put_uint8_t(buf, 28, target_num); - _mav_put_uint8_t(buf, 29, frame); - _mav_put_float(buf, 30, x); - _mav_put_float(buf, 34, y); - _mav_put_float(buf, 38, z); - _mav_put_uint8_t(buf, 58, type); - _mav_put_uint8_t(buf, 59, position_valid); - _mav_put_float_array(buf, 42, q, 4); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LANDING_TARGET, buf, MAVLINK_MSG_ID_LANDING_TARGET_MIN_LEN, MAVLINK_MSG_ID_LANDING_TARGET_LEN, MAVLINK_MSG_ID_LANDING_TARGET_CRC); -#else - mavlink_landing_target_t *packet = (mavlink_landing_target_t *)msgbuf; - packet->time_usec = time_usec; - packet->angle_x = angle_x; - packet->angle_y = angle_y; - packet->distance = distance; - packet->size_x = size_x; - packet->size_y = size_y; - packet->target_num = target_num; - packet->frame = frame; - packet->x = x; - packet->y = y; - packet->z = z; - packet->type = type; - packet->position_valid = position_valid; - mav_array_memcpy(packet->q, q, sizeof(float)*4); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LANDING_TARGET, (const char *)packet, MAVLINK_MSG_ID_LANDING_TARGET_MIN_LEN, MAVLINK_MSG_ID_LANDING_TARGET_LEN, MAVLINK_MSG_ID_LANDING_TARGET_CRC); -#endif -} -#endif - -#endif - -// MESSAGE LANDING_TARGET UNPACKING - - -/** - * @brief Get field time_usec from landing_target message - * - * @return [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - */ -static inline uint64_t mavlink_msg_landing_target_get_time_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field target_num from landing_target message - * - * @return The ID of the target if multiple targets are present - */ -static inline uint8_t mavlink_msg_landing_target_get_target_num(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 28); -} - -/** - * @brief Get field frame from landing_target message - * - * @return Coordinate frame used for following fields. - */ -static inline uint8_t mavlink_msg_landing_target_get_frame(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 29); -} - -/** - * @brief Get field angle_x from landing_target message - * - * @return [rad] X-axis angular offset of the target from the center of the image - */ -static inline float mavlink_msg_landing_target_get_angle_x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field angle_y from landing_target message - * - * @return [rad] Y-axis angular offset of the target from the center of the image - */ -static inline float mavlink_msg_landing_target_get_angle_y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field distance from landing_target message - * - * @return [m] Distance to the target from the vehicle - */ -static inline float mavlink_msg_landing_target_get_distance(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field size_x from landing_target message - * - * @return [rad] Size of target along x-axis - */ -static inline float mavlink_msg_landing_target_get_size_x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Get field size_y from landing_target message - * - * @return [rad] Size of target along y-axis - */ -static inline float mavlink_msg_landing_target_get_size_y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Get field x from landing_target message - * - * @return [m] X Position of the landing target in MAV_FRAME - */ -static inline float mavlink_msg_landing_target_get_x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 30); -} - -/** - * @brief Get field y from landing_target message - * - * @return [m] Y Position of the landing target in MAV_FRAME - */ -static inline float mavlink_msg_landing_target_get_y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 34); -} - -/** - * @brief Get field z from landing_target message - * - * @return [m] Z Position of the landing target in MAV_FRAME - */ -static inline float mavlink_msg_landing_target_get_z(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 38); -} - -/** - * @brief Get field q from landing_target message - * - * @return Quaternion of landing target orientation (w, x, y, z order, zero-rotation is 1, 0, 0, 0) - */ -static inline uint16_t mavlink_msg_landing_target_get_q(const mavlink_message_t* msg, float *q) -{ - return _MAV_RETURN_float_array(msg, q, 4, 42); -} - -/** - * @brief Get field type from landing_target message - * - * @return Type of landing target - */ -static inline uint8_t mavlink_msg_landing_target_get_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 58); -} - -/** - * @brief Get field position_valid from landing_target message - * - * @return Boolean indicating whether the position fields (x, y, z, q, type) contain valid target position information (valid: 1, invalid: 0). Default is 0 (invalid). - */ -static inline uint8_t mavlink_msg_landing_target_get_position_valid(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 59); -} - -/** - * @brief Decode a landing_target message into a struct - * - * @param msg The message to decode - * @param landing_target C-struct to decode the message contents into - */ -static inline void mavlink_msg_landing_target_decode(const mavlink_message_t* msg, mavlink_landing_target_t* landing_target) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - landing_target->time_usec = mavlink_msg_landing_target_get_time_usec(msg); - landing_target->angle_x = mavlink_msg_landing_target_get_angle_x(msg); - landing_target->angle_y = mavlink_msg_landing_target_get_angle_y(msg); - landing_target->distance = mavlink_msg_landing_target_get_distance(msg); - landing_target->size_x = mavlink_msg_landing_target_get_size_x(msg); - landing_target->size_y = mavlink_msg_landing_target_get_size_y(msg); - landing_target->target_num = mavlink_msg_landing_target_get_target_num(msg); - landing_target->frame = mavlink_msg_landing_target_get_frame(msg); - landing_target->x = mavlink_msg_landing_target_get_x(msg); - landing_target->y = mavlink_msg_landing_target_get_y(msg); - landing_target->z = mavlink_msg_landing_target_get_z(msg); - mavlink_msg_landing_target_get_q(msg, landing_target->q); - landing_target->type = mavlink_msg_landing_target_get_type(msg); - landing_target->position_valid = mavlink_msg_landing_target_get_position_valid(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_LANDING_TARGET_LEN? msg->len : MAVLINK_MSG_ID_LANDING_TARGET_LEN; - memset(landing_target, 0, MAVLINK_MSG_ID_LANDING_TARGET_LEN); - memcpy(landing_target, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_link_node_status.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_link_node_status.h deleted file mode 100644 index 927118f8..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_link_node_status.h +++ /dev/null @@ -1,463 +0,0 @@ -#pragma once -// MESSAGE LINK_NODE_STATUS PACKING - -#define MAVLINK_MSG_ID_LINK_NODE_STATUS 8 - - -typedef struct __mavlink_link_node_status_t { - uint64_t timestamp; /*< [ms] Timestamp (time since system boot).*/ - uint32_t tx_rate; /*< [bytes/s] Transmit rate*/ - uint32_t rx_rate; /*< [bytes/s] Receive rate*/ - uint32_t messages_sent; /*< Messages sent*/ - uint32_t messages_received; /*< Messages received (estimated from counting seq)*/ - uint32_t messages_lost; /*< Messages lost (estimated from counting seq)*/ - uint16_t rx_parse_err; /*< [bytes] Number of bytes that could not be parsed correctly.*/ - uint16_t tx_overflows; /*< [bytes] Transmit buffer overflows. This number wraps around as it reaches UINT16_MAX*/ - uint16_t rx_overflows; /*< [bytes] Receive buffer overflows. This number wraps around as it reaches UINT16_MAX*/ - uint8_t tx_buf; /*< [%] Remaining free transmit buffer space*/ - uint8_t rx_buf; /*< [%] Remaining free receive buffer space*/ -} mavlink_link_node_status_t; - -#define MAVLINK_MSG_ID_LINK_NODE_STATUS_LEN 36 -#define MAVLINK_MSG_ID_LINK_NODE_STATUS_MIN_LEN 36 -#define MAVLINK_MSG_ID_8_LEN 36 -#define MAVLINK_MSG_ID_8_MIN_LEN 36 - -#define MAVLINK_MSG_ID_LINK_NODE_STATUS_CRC 117 -#define MAVLINK_MSG_ID_8_CRC 117 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_LINK_NODE_STATUS { \ - 8, \ - "LINK_NODE_STATUS", \ - 11, \ - { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_link_node_status_t, timestamp) }, \ - { "tx_buf", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_link_node_status_t, tx_buf) }, \ - { "rx_buf", NULL, MAVLINK_TYPE_UINT8_T, 0, 35, offsetof(mavlink_link_node_status_t, rx_buf) }, \ - { "tx_rate", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_link_node_status_t, tx_rate) }, \ - { "rx_rate", NULL, MAVLINK_TYPE_UINT32_T, 0, 12, offsetof(mavlink_link_node_status_t, rx_rate) }, \ - { "rx_parse_err", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_link_node_status_t, rx_parse_err) }, \ - { "tx_overflows", NULL, MAVLINK_TYPE_UINT16_T, 0, 30, offsetof(mavlink_link_node_status_t, tx_overflows) }, \ - { "rx_overflows", NULL, MAVLINK_TYPE_UINT16_T, 0, 32, offsetof(mavlink_link_node_status_t, rx_overflows) }, \ - { "messages_sent", NULL, MAVLINK_TYPE_UINT32_T, 0, 16, offsetof(mavlink_link_node_status_t, messages_sent) }, \ - { "messages_received", NULL, MAVLINK_TYPE_UINT32_T, 0, 20, offsetof(mavlink_link_node_status_t, messages_received) }, \ - { "messages_lost", NULL, MAVLINK_TYPE_UINT32_T, 0, 24, offsetof(mavlink_link_node_status_t, messages_lost) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_LINK_NODE_STATUS { \ - "LINK_NODE_STATUS", \ - 11, \ - { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_link_node_status_t, timestamp) }, \ - { "tx_buf", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_link_node_status_t, tx_buf) }, \ - { "rx_buf", NULL, MAVLINK_TYPE_UINT8_T, 0, 35, offsetof(mavlink_link_node_status_t, rx_buf) }, \ - { "tx_rate", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_link_node_status_t, tx_rate) }, \ - { "rx_rate", NULL, MAVLINK_TYPE_UINT32_T, 0, 12, offsetof(mavlink_link_node_status_t, rx_rate) }, \ - { "rx_parse_err", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_link_node_status_t, rx_parse_err) }, \ - { "tx_overflows", NULL, MAVLINK_TYPE_UINT16_T, 0, 30, offsetof(mavlink_link_node_status_t, tx_overflows) }, \ - { "rx_overflows", NULL, MAVLINK_TYPE_UINT16_T, 0, 32, offsetof(mavlink_link_node_status_t, rx_overflows) }, \ - { "messages_sent", NULL, MAVLINK_TYPE_UINT32_T, 0, 16, offsetof(mavlink_link_node_status_t, messages_sent) }, \ - { "messages_received", NULL, MAVLINK_TYPE_UINT32_T, 0, 20, offsetof(mavlink_link_node_status_t, messages_received) }, \ - { "messages_lost", NULL, MAVLINK_TYPE_UINT32_T, 0, 24, offsetof(mavlink_link_node_status_t, messages_lost) }, \ - } \ -} -#endif - -/** - * @brief Pack a link_node_status message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param timestamp [ms] Timestamp (time since system boot). - * @param tx_buf [%] Remaining free transmit buffer space - * @param rx_buf [%] Remaining free receive buffer space - * @param tx_rate [bytes/s] Transmit rate - * @param rx_rate [bytes/s] Receive rate - * @param rx_parse_err [bytes] Number of bytes that could not be parsed correctly. - * @param tx_overflows [bytes] Transmit buffer overflows. This number wraps around as it reaches UINT16_MAX - * @param rx_overflows [bytes] Receive buffer overflows. This number wraps around as it reaches UINT16_MAX - * @param messages_sent Messages sent - * @param messages_received Messages received (estimated from counting seq) - * @param messages_lost Messages lost (estimated from counting seq) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_link_node_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint64_t timestamp, uint8_t tx_buf, uint8_t rx_buf, uint32_t tx_rate, uint32_t rx_rate, uint16_t rx_parse_err, uint16_t tx_overflows, uint16_t rx_overflows, uint32_t messages_sent, uint32_t messages_received, uint32_t messages_lost) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LINK_NODE_STATUS_LEN]; - _mav_put_uint64_t(buf, 0, timestamp); - _mav_put_uint32_t(buf, 8, tx_rate); - _mav_put_uint32_t(buf, 12, rx_rate); - _mav_put_uint32_t(buf, 16, messages_sent); - _mav_put_uint32_t(buf, 20, messages_received); - _mav_put_uint32_t(buf, 24, messages_lost); - _mav_put_uint16_t(buf, 28, rx_parse_err); - _mav_put_uint16_t(buf, 30, tx_overflows); - _mav_put_uint16_t(buf, 32, rx_overflows); - _mav_put_uint8_t(buf, 34, tx_buf); - _mav_put_uint8_t(buf, 35, rx_buf); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LINK_NODE_STATUS_LEN); -#else - mavlink_link_node_status_t packet; - packet.timestamp = timestamp; - packet.tx_rate = tx_rate; - packet.rx_rate = rx_rate; - packet.messages_sent = messages_sent; - packet.messages_received = messages_received; - packet.messages_lost = messages_lost; - packet.rx_parse_err = rx_parse_err; - packet.tx_overflows = tx_overflows; - packet.rx_overflows = rx_overflows; - packet.tx_buf = tx_buf; - packet.rx_buf = rx_buf; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LINK_NODE_STATUS_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_LINK_NODE_STATUS; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LINK_NODE_STATUS_MIN_LEN, MAVLINK_MSG_ID_LINK_NODE_STATUS_LEN, MAVLINK_MSG_ID_LINK_NODE_STATUS_CRC); -} - -/** - * @brief Pack a link_node_status message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param timestamp [ms] Timestamp (time since system boot). - * @param tx_buf [%] Remaining free transmit buffer space - * @param rx_buf [%] Remaining free receive buffer space - * @param tx_rate [bytes/s] Transmit rate - * @param rx_rate [bytes/s] Receive rate - * @param rx_parse_err [bytes] Number of bytes that could not be parsed correctly. - * @param tx_overflows [bytes] Transmit buffer overflows. This number wraps around as it reaches UINT16_MAX - * @param rx_overflows [bytes] Receive buffer overflows. This number wraps around as it reaches UINT16_MAX - * @param messages_sent Messages sent - * @param messages_received Messages received (estimated from counting seq) - * @param messages_lost Messages lost (estimated from counting seq) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_link_node_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint64_t timestamp,uint8_t tx_buf,uint8_t rx_buf,uint32_t tx_rate,uint32_t rx_rate,uint16_t rx_parse_err,uint16_t tx_overflows,uint16_t rx_overflows,uint32_t messages_sent,uint32_t messages_received,uint32_t messages_lost) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LINK_NODE_STATUS_LEN]; - _mav_put_uint64_t(buf, 0, timestamp); - _mav_put_uint32_t(buf, 8, tx_rate); - _mav_put_uint32_t(buf, 12, rx_rate); - _mav_put_uint32_t(buf, 16, messages_sent); - _mav_put_uint32_t(buf, 20, messages_received); - _mav_put_uint32_t(buf, 24, messages_lost); - _mav_put_uint16_t(buf, 28, rx_parse_err); - _mav_put_uint16_t(buf, 30, tx_overflows); - _mav_put_uint16_t(buf, 32, rx_overflows); - _mav_put_uint8_t(buf, 34, tx_buf); - _mav_put_uint8_t(buf, 35, rx_buf); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LINK_NODE_STATUS_LEN); -#else - mavlink_link_node_status_t packet; - packet.timestamp = timestamp; - packet.tx_rate = tx_rate; - packet.rx_rate = rx_rate; - packet.messages_sent = messages_sent; - packet.messages_received = messages_received; - packet.messages_lost = messages_lost; - packet.rx_parse_err = rx_parse_err; - packet.tx_overflows = tx_overflows; - packet.rx_overflows = rx_overflows; - packet.tx_buf = tx_buf; - packet.rx_buf = rx_buf; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LINK_NODE_STATUS_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_LINK_NODE_STATUS; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LINK_NODE_STATUS_MIN_LEN, MAVLINK_MSG_ID_LINK_NODE_STATUS_LEN, MAVLINK_MSG_ID_LINK_NODE_STATUS_CRC); -} - -/** - * @brief Encode a link_node_status struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param link_node_status C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_link_node_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_link_node_status_t* link_node_status) -{ - return mavlink_msg_link_node_status_pack(system_id, component_id, msg, link_node_status->timestamp, link_node_status->tx_buf, link_node_status->rx_buf, link_node_status->tx_rate, link_node_status->rx_rate, link_node_status->rx_parse_err, link_node_status->tx_overflows, link_node_status->rx_overflows, link_node_status->messages_sent, link_node_status->messages_received, link_node_status->messages_lost); -} - -/** - * @brief Encode a link_node_status struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param link_node_status C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_link_node_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_link_node_status_t* link_node_status) -{ - return mavlink_msg_link_node_status_pack_chan(system_id, component_id, chan, msg, link_node_status->timestamp, link_node_status->tx_buf, link_node_status->rx_buf, link_node_status->tx_rate, link_node_status->rx_rate, link_node_status->rx_parse_err, link_node_status->tx_overflows, link_node_status->rx_overflows, link_node_status->messages_sent, link_node_status->messages_received, link_node_status->messages_lost); -} - -/** - * @brief Send a link_node_status message - * @param chan MAVLink channel to send the message - * - * @param timestamp [ms] Timestamp (time since system boot). - * @param tx_buf [%] Remaining free transmit buffer space - * @param rx_buf [%] Remaining free receive buffer space - * @param tx_rate [bytes/s] Transmit rate - * @param rx_rate [bytes/s] Receive rate - * @param rx_parse_err [bytes] Number of bytes that could not be parsed correctly. - * @param tx_overflows [bytes] Transmit buffer overflows. This number wraps around as it reaches UINT16_MAX - * @param rx_overflows [bytes] Receive buffer overflows. This number wraps around as it reaches UINT16_MAX - * @param messages_sent Messages sent - * @param messages_received Messages received (estimated from counting seq) - * @param messages_lost Messages lost (estimated from counting seq) - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_link_node_status_send(mavlink_channel_t chan, uint64_t timestamp, uint8_t tx_buf, uint8_t rx_buf, uint32_t tx_rate, uint32_t rx_rate, uint16_t rx_parse_err, uint16_t tx_overflows, uint16_t rx_overflows, uint32_t messages_sent, uint32_t messages_received, uint32_t messages_lost) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LINK_NODE_STATUS_LEN]; - _mav_put_uint64_t(buf, 0, timestamp); - _mav_put_uint32_t(buf, 8, tx_rate); - _mav_put_uint32_t(buf, 12, rx_rate); - _mav_put_uint32_t(buf, 16, messages_sent); - _mav_put_uint32_t(buf, 20, messages_received); - _mav_put_uint32_t(buf, 24, messages_lost); - _mav_put_uint16_t(buf, 28, rx_parse_err); - _mav_put_uint16_t(buf, 30, tx_overflows); - _mav_put_uint16_t(buf, 32, rx_overflows); - _mav_put_uint8_t(buf, 34, tx_buf); - _mav_put_uint8_t(buf, 35, rx_buf); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LINK_NODE_STATUS, buf, MAVLINK_MSG_ID_LINK_NODE_STATUS_MIN_LEN, MAVLINK_MSG_ID_LINK_NODE_STATUS_LEN, MAVLINK_MSG_ID_LINK_NODE_STATUS_CRC); -#else - mavlink_link_node_status_t packet; - packet.timestamp = timestamp; - packet.tx_rate = tx_rate; - packet.rx_rate = rx_rate; - packet.messages_sent = messages_sent; - packet.messages_received = messages_received; - packet.messages_lost = messages_lost; - packet.rx_parse_err = rx_parse_err; - packet.tx_overflows = tx_overflows; - packet.rx_overflows = rx_overflows; - packet.tx_buf = tx_buf; - packet.rx_buf = rx_buf; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LINK_NODE_STATUS, (const char *)&packet, MAVLINK_MSG_ID_LINK_NODE_STATUS_MIN_LEN, MAVLINK_MSG_ID_LINK_NODE_STATUS_LEN, MAVLINK_MSG_ID_LINK_NODE_STATUS_CRC); -#endif -} - -/** - * @brief Send a link_node_status message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_link_node_status_send_struct(mavlink_channel_t chan, const mavlink_link_node_status_t* link_node_status) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_link_node_status_send(chan, link_node_status->timestamp, link_node_status->tx_buf, link_node_status->rx_buf, link_node_status->tx_rate, link_node_status->rx_rate, link_node_status->rx_parse_err, link_node_status->tx_overflows, link_node_status->rx_overflows, link_node_status->messages_sent, link_node_status->messages_received, link_node_status->messages_lost); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LINK_NODE_STATUS, (const char *)link_node_status, MAVLINK_MSG_ID_LINK_NODE_STATUS_MIN_LEN, MAVLINK_MSG_ID_LINK_NODE_STATUS_LEN, MAVLINK_MSG_ID_LINK_NODE_STATUS_CRC); -#endif -} - -#if MAVLINK_MSG_ID_LINK_NODE_STATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_link_node_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp, uint8_t tx_buf, uint8_t rx_buf, uint32_t tx_rate, uint32_t rx_rate, uint16_t rx_parse_err, uint16_t tx_overflows, uint16_t rx_overflows, uint32_t messages_sent, uint32_t messages_received, uint32_t messages_lost) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, timestamp); - _mav_put_uint32_t(buf, 8, tx_rate); - _mav_put_uint32_t(buf, 12, rx_rate); - _mav_put_uint32_t(buf, 16, messages_sent); - _mav_put_uint32_t(buf, 20, messages_received); - _mav_put_uint32_t(buf, 24, messages_lost); - _mav_put_uint16_t(buf, 28, rx_parse_err); - _mav_put_uint16_t(buf, 30, tx_overflows); - _mav_put_uint16_t(buf, 32, rx_overflows); - _mav_put_uint8_t(buf, 34, tx_buf); - _mav_put_uint8_t(buf, 35, rx_buf); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LINK_NODE_STATUS, buf, MAVLINK_MSG_ID_LINK_NODE_STATUS_MIN_LEN, MAVLINK_MSG_ID_LINK_NODE_STATUS_LEN, MAVLINK_MSG_ID_LINK_NODE_STATUS_CRC); -#else - mavlink_link_node_status_t *packet = (mavlink_link_node_status_t *)msgbuf; - packet->timestamp = timestamp; - packet->tx_rate = tx_rate; - packet->rx_rate = rx_rate; - packet->messages_sent = messages_sent; - packet->messages_received = messages_received; - packet->messages_lost = messages_lost; - packet->rx_parse_err = rx_parse_err; - packet->tx_overflows = tx_overflows; - packet->rx_overflows = rx_overflows; - packet->tx_buf = tx_buf; - packet->rx_buf = rx_buf; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LINK_NODE_STATUS, (const char *)packet, MAVLINK_MSG_ID_LINK_NODE_STATUS_MIN_LEN, MAVLINK_MSG_ID_LINK_NODE_STATUS_LEN, MAVLINK_MSG_ID_LINK_NODE_STATUS_CRC); -#endif -} -#endif - -#endif - -// MESSAGE LINK_NODE_STATUS UNPACKING - - -/** - * @brief Get field timestamp from link_node_status message - * - * @return [ms] Timestamp (time since system boot). - */ -static inline uint64_t mavlink_msg_link_node_status_get_timestamp(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field tx_buf from link_node_status message - * - * @return [%] Remaining free transmit buffer space - */ -static inline uint8_t mavlink_msg_link_node_status_get_tx_buf(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 34); -} - -/** - * @brief Get field rx_buf from link_node_status message - * - * @return [%] Remaining free receive buffer space - */ -static inline uint8_t mavlink_msg_link_node_status_get_rx_buf(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 35); -} - -/** - * @brief Get field tx_rate from link_node_status message - * - * @return [bytes/s] Transmit rate - */ -static inline uint32_t mavlink_msg_link_node_status_get_tx_rate(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 8); -} - -/** - * @brief Get field rx_rate from link_node_status message - * - * @return [bytes/s] Receive rate - */ -static inline uint32_t mavlink_msg_link_node_status_get_rx_rate(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 12); -} - -/** - * @brief Get field rx_parse_err from link_node_status message - * - * @return [bytes] Number of bytes that could not be parsed correctly. - */ -static inline uint16_t mavlink_msg_link_node_status_get_rx_parse_err(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 28); -} - -/** - * @brief Get field tx_overflows from link_node_status message - * - * @return [bytes] Transmit buffer overflows. This number wraps around as it reaches UINT16_MAX - */ -static inline uint16_t mavlink_msg_link_node_status_get_tx_overflows(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 30); -} - -/** - * @brief Get field rx_overflows from link_node_status message - * - * @return [bytes] Receive buffer overflows. This number wraps around as it reaches UINT16_MAX - */ -static inline uint16_t mavlink_msg_link_node_status_get_rx_overflows(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 32); -} - -/** - * @brief Get field messages_sent from link_node_status message - * - * @return Messages sent - */ -static inline uint32_t mavlink_msg_link_node_status_get_messages_sent(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 16); -} - -/** - * @brief Get field messages_received from link_node_status message - * - * @return Messages received (estimated from counting seq) - */ -static inline uint32_t mavlink_msg_link_node_status_get_messages_received(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 20); -} - -/** - * @brief Get field messages_lost from link_node_status message - * - * @return Messages lost (estimated from counting seq) - */ -static inline uint32_t mavlink_msg_link_node_status_get_messages_lost(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 24); -} - -/** - * @brief Decode a link_node_status message into a struct - * - * @param msg The message to decode - * @param link_node_status C-struct to decode the message contents into - */ -static inline void mavlink_msg_link_node_status_decode(const mavlink_message_t* msg, mavlink_link_node_status_t* link_node_status) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - link_node_status->timestamp = mavlink_msg_link_node_status_get_timestamp(msg); - link_node_status->tx_rate = mavlink_msg_link_node_status_get_tx_rate(msg); - link_node_status->rx_rate = mavlink_msg_link_node_status_get_rx_rate(msg); - link_node_status->messages_sent = mavlink_msg_link_node_status_get_messages_sent(msg); - link_node_status->messages_received = mavlink_msg_link_node_status_get_messages_received(msg); - link_node_status->messages_lost = mavlink_msg_link_node_status_get_messages_lost(msg); - link_node_status->rx_parse_err = mavlink_msg_link_node_status_get_rx_parse_err(msg); - link_node_status->tx_overflows = mavlink_msg_link_node_status_get_tx_overflows(msg); - link_node_status->rx_overflows = mavlink_msg_link_node_status_get_rx_overflows(msg); - link_node_status->tx_buf = mavlink_msg_link_node_status_get_tx_buf(msg); - link_node_status->rx_buf = mavlink_msg_link_node_status_get_rx_buf(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_LINK_NODE_STATUS_LEN? msg->len : MAVLINK_MSG_ID_LINK_NODE_STATUS_LEN; - memset(link_node_status, 0, MAVLINK_MSG_ID_LINK_NODE_STATUS_LEN); - memcpy(link_node_status, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_local_position_ned.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_local_position_ned.h deleted file mode 100644 index a84fca84..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_local_position_ned.h +++ /dev/null @@ -1,363 +0,0 @@ -#pragma once -// MESSAGE LOCAL_POSITION_NED PACKING - -#define MAVLINK_MSG_ID_LOCAL_POSITION_NED 32 - - -typedef struct __mavlink_local_position_ned_t { - uint32_t time_boot_ms; /*< [ms] Timestamp (time since system boot).*/ - float x; /*< [m] X Position*/ - float y; /*< [m] Y Position*/ - float z; /*< [m] Z Position*/ - float vx; /*< [m/s] X Speed*/ - float vy; /*< [m/s] Y Speed*/ - float vz; /*< [m/s] Z Speed*/ -} mavlink_local_position_ned_t; - -#define MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN 28 -#define MAVLINK_MSG_ID_LOCAL_POSITION_NED_MIN_LEN 28 -#define MAVLINK_MSG_ID_32_LEN 28 -#define MAVLINK_MSG_ID_32_MIN_LEN 28 - -#define MAVLINK_MSG_ID_LOCAL_POSITION_NED_CRC 185 -#define MAVLINK_MSG_ID_32_CRC 185 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED { \ - 32, \ - "LOCAL_POSITION_NED", \ - 7, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_local_position_ned_t, time_boot_ms) }, \ - { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_local_position_ned_t, x) }, \ - { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_local_position_ned_t, y) }, \ - { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_local_position_ned_t, z) }, \ - { "vx", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_local_position_ned_t, vx) }, \ - { "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_local_position_ned_t, vy) }, \ - { "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_local_position_ned_t, vz) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED { \ - "LOCAL_POSITION_NED", \ - 7, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_local_position_ned_t, time_boot_ms) }, \ - { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_local_position_ned_t, x) }, \ - { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_local_position_ned_t, y) }, \ - { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_local_position_ned_t, z) }, \ - { "vx", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_local_position_ned_t, vx) }, \ - { "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_local_position_ned_t, vy) }, \ - { "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_local_position_ned_t, vz) }, \ - } \ -} -#endif - -/** - * @brief Pack a local_position_ned message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param time_boot_ms [ms] Timestamp (time since system boot). - * @param x [m] X Position - * @param y [m] Y Position - * @param z [m] Z Position - * @param vx [m/s] X Speed - * @param vy [m/s] Y Speed - * @param vz [m/s] Z Speed - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_local_position_ned_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint32_t time_boot_ms, float x, float y, float z, float vx, float vy, float vz) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, x); - _mav_put_float(buf, 8, y); - _mav_put_float(buf, 12, z); - _mav_put_float(buf, 16, vx); - _mav_put_float(buf, 20, vy); - _mav_put_float(buf, 24, vz); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN); -#else - mavlink_local_position_ned_t packet; - packet.time_boot_ms = time_boot_ms; - packet.x = x; - packet.y = y; - packet.z = z; - packet.vx = vx; - packet.vy = vy; - packet.vz = vz; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_LOCAL_POSITION_NED; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOCAL_POSITION_NED_MIN_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_CRC); -} - -/** - * @brief Pack a local_position_ned message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_boot_ms [ms] Timestamp (time since system boot). - * @param x [m] X Position - * @param y [m] Y Position - * @param z [m] Z Position - * @param vx [m/s] X Speed - * @param vy [m/s] Y Speed - * @param vz [m/s] Z Speed - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_local_position_ned_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint32_t time_boot_ms,float x,float y,float z,float vx,float vy,float vz) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, x); - _mav_put_float(buf, 8, y); - _mav_put_float(buf, 12, z); - _mav_put_float(buf, 16, vx); - _mav_put_float(buf, 20, vy); - _mav_put_float(buf, 24, vz); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN); -#else - mavlink_local_position_ned_t packet; - packet.time_boot_ms = time_boot_ms; - packet.x = x; - packet.y = y; - packet.z = z; - packet.vx = vx; - packet.vy = vy; - packet.vz = vz; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_LOCAL_POSITION_NED; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_MIN_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_CRC); -} - -/** - * @brief Encode a local_position_ned struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param local_position_ned C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_local_position_ned_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_local_position_ned_t* local_position_ned) -{ - return mavlink_msg_local_position_ned_pack(system_id, component_id, msg, local_position_ned->time_boot_ms, local_position_ned->x, local_position_ned->y, local_position_ned->z, local_position_ned->vx, local_position_ned->vy, local_position_ned->vz); -} - -/** - * @brief Encode a local_position_ned struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param local_position_ned C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_local_position_ned_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_local_position_ned_t* local_position_ned) -{ - return mavlink_msg_local_position_ned_pack_chan(system_id, component_id, chan, msg, local_position_ned->time_boot_ms, local_position_ned->x, local_position_ned->y, local_position_ned->z, local_position_ned->vx, local_position_ned->vy, local_position_ned->vz); -} - -/** - * @brief Send a local_position_ned message - * @param chan MAVLink channel to send the message - * - * @param time_boot_ms [ms] Timestamp (time since system boot). - * @param x [m] X Position - * @param y [m] Y Position - * @param z [m] Z Position - * @param vx [m/s] X Speed - * @param vy [m/s] Y Speed - * @param vz [m/s] Z Speed - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_local_position_ned_send(mavlink_channel_t chan, uint32_t time_boot_ms, float x, float y, float z, float vx, float vy, float vz) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, x); - _mav_put_float(buf, 8, y); - _mav_put_float(buf, 12, z); - _mav_put_float(buf, 16, vx); - _mav_put_float(buf, 20, vy); - _mav_put_float(buf, 24, vz); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED, buf, MAVLINK_MSG_ID_LOCAL_POSITION_NED_MIN_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_CRC); -#else - mavlink_local_position_ned_t packet; - packet.time_boot_ms = time_boot_ms; - packet.x = x; - packet.y = y; - packet.z = z; - packet.vx = vx; - packet.vy = vy; - packet.vz = vz; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED, (const char *)&packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_MIN_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_CRC); -#endif -} - -/** - * @brief Send a local_position_ned message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_local_position_ned_send_struct(mavlink_channel_t chan, const mavlink_local_position_ned_t* local_position_ned) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_local_position_ned_send(chan, local_position_ned->time_boot_ms, local_position_ned->x, local_position_ned->y, local_position_ned->z, local_position_ned->vx, local_position_ned->vy, local_position_ned->vz); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED, (const char *)local_position_ned, MAVLINK_MSG_ID_LOCAL_POSITION_NED_MIN_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_CRC); -#endif -} - -#if MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_local_position_ned_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, float x, float y, float z, float vx, float vy, float vz) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, x); - _mav_put_float(buf, 8, y); - _mav_put_float(buf, 12, z); - _mav_put_float(buf, 16, vx); - _mav_put_float(buf, 20, vy); - _mav_put_float(buf, 24, vz); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED, buf, MAVLINK_MSG_ID_LOCAL_POSITION_NED_MIN_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_CRC); -#else - mavlink_local_position_ned_t *packet = (mavlink_local_position_ned_t *)msgbuf; - packet->time_boot_ms = time_boot_ms; - packet->x = x; - packet->y = y; - packet->z = z; - packet->vx = vx; - packet->vy = vy; - packet->vz = vz; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED, (const char *)packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_MIN_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_CRC); -#endif -} -#endif - -#endif - -// MESSAGE LOCAL_POSITION_NED UNPACKING - - -/** - * @brief Get field time_boot_ms from local_position_ned message - * - * @return [ms] Timestamp (time since system boot). - */ -static inline uint32_t mavlink_msg_local_position_ned_get_time_boot_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field x from local_position_ned message - * - * @return [m] X Position - */ -static inline float mavlink_msg_local_position_ned_get_x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 4); -} - -/** - * @brief Get field y from local_position_ned message - * - * @return [m] Y Position - */ -static inline float mavlink_msg_local_position_ned_get_y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field z from local_position_ned message - * - * @return [m] Z Position - */ -static inline float mavlink_msg_local_position_ned_get_z(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field vx from local_position_ned message - * - * @return [m/s] X Speed - */ -static inline float mavlink_msg_local_position_ned_get_vx(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field vy from local_position_ned message - * - * @return [m/s] Y Speed - */ -static inline float mavlink_msg_local_position_ned_get_vy(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Get field vz from local_position_ned message - * - * @return [m/s] Z Speed - */ -static inline float mavlink_msg_local_position_ned_get_vz(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Decode a local_position_ned message into a struct - * - * @param msg The message to decode - * @param local_position_ned C-struct to decode the message contents into - */ -static inline void mavlink_msg_local_position_ned_decode(const mavlink_message_t* msg, mavlink_local_position_ned_t* local_position_ned) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - local_position_ned->time_boot_ms = mavlink_msg_local_position_ned_get_time_boot_ms(msg); - local_position_ned->x = mavlink_msg_local_position_ned_get_x(msg); - local_position_ned->y = mavlink_msg_local_position_ned_get_y(msg); - local_position_ned->z = mavlink_msg_local_position_ned_get_z(msg); - local_position_ned->vx = mavlink_msg_local_position_ned_get_vx(msg); - local_position_ned->vy = mavlink_msg_local_position_ned_get_vy(msg); - local_position_ned->vz = mavlink_msg_local_position_ned_get_vz(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN? msg->len : MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN; - memset(local_position_ned, 0, MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN); - memcpy(local_position_ned, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_local_position_ned_cov.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_local_position_ned_cov.h deleted file mode 100644 index b7eeba49..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_local_position_ned_cov.h +++ /dev/null @@ -1,480 +0,0 @@ -#pragma once -// MESSAGE LOCAL_POSITION_NED_COV PACKING - -#define MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV 64 - - -typedef struct __mavlink_local_position_ned_cov_t { - uint64_t time_usec; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/ - float x; /*< [m] X Position*/ - float y; /*< [m] Y Position*/ - float z; /*< [m] Z Position*/ - float vx; /*< [m/s] X Speed*/ - float vy; /*< [m/s] Y Speed*/ - float vz; /*< [m/s] Z Speed*/ - float ax; /*< [m/s/s] X Acceleration*/ - float ay; /*< [m/s/s] Y Acceleration*/ - float az; /*< [m/s/s] Z Acceleration*/ - float covariance[45]; /*< Row-major representation of position, velocity and acceleration 9x9 cross-covariance matrix upper right triangle (states: x, y, z, vx, vy, vz, ax, ay, az; first nine entries are the first ROW, next eight entries are the second row, etc.). If unknown, assign NaN value to first element in the array.*/ - uint8_t estimator_type; /*< Class id of the estimator this estimate originated from.*/ -} mavlink_local_position_ned_cov_t; - -#define MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN 225 -#define MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_MIN_LEN 225 -#define MAVLINK_MSG_ID_64_LEN 225 -#define MAVLINK_MSG_ID_64_MIN_LEN 225 - -#define MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_CRC 191 -#define MAVLINK_MSG_ID_64_CRC 191 - -#define MAVLINK_MSG_LOCAL_POSITION_NED_COV_FIELD_COVARIANCE_LEN 45 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED_COV { \ - 64, \ - "LOCAL_POSITION_NED_COV", \ - 12, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_local_position_ned_cov_t, time_usec) }, \ - { "estimator_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 224, offsetof(mavlink_local_position_ned_cov_t, estimator_type) }, \ - { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_local_position_ned_cov_t, x) }, \ - { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_local_position_ned_cov_t, y) }, \ - { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_local_position_ned_cov_t, z) }, \ - { "vx", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_local_position_ned_cov_t, vx) }, \ - { "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_local_position_ned_cov_t, vy) }, \ - { "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_local_position_ned_cov_t, vz) }, \ - { "ax", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_local_position_ned_cov_t, ax) }, \ - { "ay", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_local_position_ned_cov_t, ay) }, \ - { "az", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_local_position_ned_cov_t, az) }, \ - { "covariance", NULL, MAVLINK_TYPE_FLOAT, 45, 44, offsetof(mavlink_local_position_ned_cov_t, covariance) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED_COV { \ - "LOCAL_POSITION_NED_COV", \ - 12, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_local_position_ned_cov_t, time_usec) }, \ - { "estimator_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 224, offsetof(mavlink_local_position_ned_cov_t, estimator_type) }, \ - { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_local_position_ned_cov_t, x) }, \ - { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_local_position_ned_cov_t, y) }, \ - { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_local_position_ned_cov_t, z) }, \ - { "vx", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_local_position_ned_cov_t, vx) }, \ - { "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_local_position_ned_cov_t, vy) }, \ - { "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_local_position_ned_cov_t, vz) }, \ - { "ax", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_local_position_ned_cov_t, ax) }, \ - { "ay", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_local_position_ned_cov_t, ay) }, \ - { "az", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_local_position_ned_cov_t, az) }, \ - { "covariance", NULL, MAVLINK_TYPE_FLOAT, 45, 44, offsetof(mavlink_local_position_ned_cov_t, covariance) }, \ - } \ -} -#endif - -/** - * @brief Pack a local_position_ned_cov message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @param estimator_type Class id of the estimator this estimate originated from. - * @param x [m] X Position - * @param y [m] Y Position - * @param z [m] Z Position - * @param vx [m/s] X Speed - * @param vy [m/s] Y Speed - * @param vz [m/s] Z Speed - * @param ax [m/s/s] X Acceleration - * @param ay [m/s/s] Y Acceleration - * @param az [m/s/s] Z Acceleration - * @param covariance Row-major representation of position, velocity and acceleration 9x9 cross-covariance matrix upper right triangle (states: x, y, z, vx, vy, vz, ax, ay, az; first nine entries are the first ROW, next eight entries are the second row, etc.). If unknown, assign NaN value to first element in the array. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_local_position_ned_cov_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint64_t time_usec, uint8_t estimator_type, float x, float y, float z, float vx, float vy, float vz, float ax, float ay, float az, const float *covariance) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, x); - _mav_put_float(buf, 12, y); - _mav_put_float(buf, 16, z); - _mav_put_float(buf, 20, vx); - _mav_put_float(buf, 24, vy); - _mav_put_float(buf, 28, vz); - _mav_put_float(buf, 32, ax); - _mav_put_float(buf, 36, ay); - _mav_put_float(buf, 40, az); - _mav_put_uint8_t(buf, 224, estimator_type); - _mav_put_float_array(buf, 44, covariance, 45); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN); -#else - mavlink_local_position_ned_cov_t packet; - packet.time_usec = time_usec; - packet.x = x; - packet.y = y; - packet.z = z; - packet.vx = vx; - packet.vy = vy; - packet.vz = vz; - packet.ax = ax; - packet.ay = ay; - packet.az = az; - packet.estimator_type = estimator_type; - mav_array_memcpy(packet.covariance, covariance, sizeof(float)*45); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_MIN_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_CRC); -} - -/** - * @brief Pack a local_position_ned_cov message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @param estimator_type Class id of the estimator this estimate originated from. - * @param x [m] X Position - * @param y [m] Y Position - * @param z [m] Z Position - * @param vx [m/s] X Speed - * @param vy [m/s] Y Speed - * @param vz [m/s] Z Speed - * @param ax [m/s/s] X Acceleration - * @param ay [m/s/s] Y Acceleration - * @param az [m/s/s] Z Acceleration - * @param covariance Row-major representation of position, velocity and acceleration 9x9 cross-covariance matrix upper right triangle (states: x, y, z, vx, vy, vz, ax, ay, az; first nine entries are the first ROW, next eight entries are the second row, etc.). If unknown, assign NaN value to first element in the array. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_local_position_ned_cov_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint64_t time_usec,uint8_t estimator_type,float x,float y,float z,float vx,float vy,float vz,float ax,float ay,float az,const float *covariance) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, x); - _mav_put_float(buf, 12, y); - _mav_put_float(buf, 16, z); - _mav_put_float(buf, 20, vx); - _mav_put_float(buf, 24, vy); - _mav_put_float(buf, 28, vz); - _mav_put_float(buf, 32, ax); - _mav_put_float(buf, 36, ay); - _mav_put_float(buf, 40, az); - _mav_put_uint8_t(buf, 224, estimator_type); - _mav_put_float_array(buf, 44, covariance, 45); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN); -#else - mavlink_local_position_ned_cov_t packet; - packet.time_usec = time_usec; - packet.x = x; - packet.y = y; - packet.z = z; - packet.vx = vx; - packet.vy = vy; - packet.vz = vz; - packet.ax = ax; - packet.ay = ay; - packet.az = az; - packet.estimator_type = estimator_type; - mav_array_memcpy(packet.covariance, covariance, sizeof(float)*45); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_MIN_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_CRC); -} - -/** - * @brief Encode a local_position_ned_cov struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param local_position_ned_cov C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_local_position_ned_cov_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_local_position_ned_cov_t* local_position_ned_cov) -{ - return mavlink_msg_local_position_ned_cov_pack(system_id, component_id, msg, local_position_ned_cov->time_usec, local_position_ned_cov->estimator_type, local_position_ned_cov->x, local_position_ned_cov->y, local_position_ned_cov->z, local_position_ned_cov->vx, local_position_ned_cov->vy, local_position_ned_cov->vz, local_position_ned_cov->ax, local_position_ned_cov->ay, local_position_ned_cov->az, local_position_ned_cov->covariance); -} - -/** - * @brief Encode a local_position_ned_cov struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param local_position_ned_cov C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_local_position_ned_cov_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_local_position_ned_cov_t* local_position_ned_cov) -{ - return mavlink_msg_local_position_ned_cov_pack_chan(system_id, component_id, chan, msg, local_position_ned_cov->time_usec, local_position_ned_cov->estimator_type, local_position_ned_cov->x, local_position_ned_cov->y, local_position_ned_cov->z, local_position_ned_cov->vx, local_position_ned_cov->vy, local_position_ned_cov->vz, local_position_ned_cov->ax, local_position_ned_cov->ay, local_position_ned_cov->az, local_position_ned_cov->covariance); -} - -/** - * @brief Send a local_position_ned_cov message - * @param chan MAVLink channel to send the message - * - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @param estimator_type Class id of the estimator this estimate originated from. - * @param x [m] X Position - * @param y [m] Y Position - * @param z [m] Z Position - * @param vx [m/s] X Speed - * @param vy [m/s] Y Speed - * @param vz [m/s] Z Speed - * @param ax [m/s/s] X Acceleration - * @param ay [m/s/s] Y Acceleration - * @param az [m/s/s] Z Acceleration - * @param covariance Row-major representation of position, velocity and acceleration 9x9 cross-covariance matrix upper right triangle (states: x, y, z, vx, vy, vz, ax, ay, az; first nine entries are the first ROW, next eight entries are the second row, etc.). If unknown, assign NaN value to first element in the array. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_local_position_ned_cov_send(mavlink_channel_t chan, uint64_t time_usec, uint8_t estimator_type, float x, float y, float z, float vx, float vy, float vz, float ax, float ay, float az, const float *covariance) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, x); - _mav_put_float(buf, 12, y); - _mav_put_float(buf, 16, z); - _mav_put_float(buf, 20, vx); - _mav_put_float(buf, 24, vy); - _mav_put_float(buf, 28, vz); - _mav_put_float(buf, 32, ax); - _mav_put_float(buf, 36, ay); - _mav_put_float(buf, 40, az); - _mav_put_uint8_t(buf, 224, estimator_type); - _mav_put_float_array(buf, 44, covariance, 45); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV, buf, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_MIN_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_CRC); -#else - mavlink_local_position_ned_cov_t packet; - packet.time_usec = time_usec; - packet.x = x; - packet.y = y; - packet.z = z; - packet.vx = vx; - packet.vy = vy; - packet.vz = vz; - packet.ax = ax; - packet.ay = ay; - packet.az = az; - packet.estimator_type = estimator_type; - mav_array_memcpy(packet.covariance, covariance, sizeof(float)*45); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV, (const char *)&packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_MIN_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_CRC); -#endif -} - -/** - * @brief Send a local_position_ned_cov message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_local_position_ned_cov_send_struct(mavlink_channel_t chan, const mavlink_local_position_ned_cov_t* local_position_ned_cov) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_local_position_ned_cov_send(chan, local_position_ned_cov->time_usec, local_position_ned_cov->estimator_type, local_position_ned_cov->x, local_position_ned_cov->y, local_position_ned_cov->z, local_position_ned_cov->vx, local_position_ned_cov->vy, local_position_ned_cov->vz, local_position_ned_cov->ax, local_position_ned_cov->ay, local_position_ned_cov->az, local_position_ned_cov->covariance); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV, (const char *)local_position_ned_cov, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_MIN_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_CRC); -#endif -} - -#if MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_local_position_ned_cov_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, uint8_t estimator_type, float x, float y, float z, float vx, float vy, float vz, float ax, float ay, float az, const float *covariance) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, x); - _mav_put_float(buf, 12, y); - _mav_put_float(buf, 16, z); - _mav_put_float(buf, 20, vx); - _mav_put_float(buf, 24, vy); - _mav_put_float(buf, 28, vz); - _mav_put_float(buf, 32, ax); - _mav_put_float(buf, 36, ay); - _mav_put_float(buf, 40, az); - _mav_put_uint8_t(buf, 224, estimator_type); - _mav_put_float_array(buf, 44, covariance, 45); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV, buf, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_MIN_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_CRC); -#else - mavlink_local_position_ned_cov_t *packet = (mavlink_local_position_ned_cov_t *)msgbuf; - packet->time_usec = time_usec; - packet->x = x; - packet->y = y; - packet->z = z; - packet->vx = vx; - packet->vy = vy; - packet->vz = vz; - packet->ax = ax; - packet->ay = ay; - packet->az = az; - packet->estimator_type = estimator_type; - mav_array_memcpy(packet->covariance, covariance, sizeof(float)*45); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV, (const char *)packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_MIN_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_CRC); -#endif -} -#endif - -#endif - -// MESSAGE LOCAL_POSITION_NED_COV UNPACKING - - -/** - * @brief Get field time_usec from local_position_ned_cov message - * - * @return [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - */ -static inline uint64_t mavlink_msg_local_position_ned_cov_get_time_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field estimator_type from local_position_ned_cov message - * - * @return Class id of the estimator this estimate originated from. - */ -static inline uint8_t mavlink_msg_local_position_ned_cov_get_estimator_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 224); -} - -/** - * @brief Get field x from local_position_ned_cov message - * - * @return [m] X Position - */ -static inline float mavlink_msg_local_position_ned_cov_get_x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field y from local_position_ned_cov message - * - * @return [m] Y Position - */ -static inline float mavlink_msg_local_position_ned_cov_get_y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field z from local_position_ned_cov message - * - * @return [m] Z Position - */ -static inline float mavlink_msg_local_position_ned_cov_get_z(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field vx from local_position_ned_cov message - * - * @return [m/s] X Speed - */ -static inline float mavlink_msg_local_position_ned_cov_get_vx(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Get field vy from local_position_ned_cov message - * - * @return [m/s] Y Speed - */ -static inline float mavlink_msg_local_position_ned_cov_get_vy(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Get field vz from local_position_ned_cov message - * - * @return [m/s] Z Speed - */ -static inline float mavlink_msg_local_position_ned_cov_get_vz(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 28); -} - -/** - * @brief Get field ax from local_position_ned_cov message - * - * @return [m/s/s] X Acceleration - */ -static inline float mavlink_msg_local_position_ned_cov_get_ax(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 32); -} - -/** - * @brief Get field ay from local_position_ned_cov message - * - * @return [m/s/s] Y Acceleration - */ -static inline float mavlink_msg_local_position_ned_cov_get_ay(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 36); -} - -/** - * @brief Get field az from local_position_ned_cov message - * - * @return [m/s/s] Z Acceleration - */ -static inline float mavlink_msg_local_position_ned_cov_get_az(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 40); -} - -/** - * @brief Get field covariance from local_position_ned_cov message - * - * @return Row-major representation of position, velocity and acceleration 9x9 cross-covariance matrix upper right triangle (states: x, y, z, vx, vy, vz, ax, ay, az; first nine entries are the first ROW, next eight entries are the second row, etc.). If unknown, assign NaN value to first element in the array. - */ -static inline uint16_t mavlink_msg_local_position_ned_cov_get_covariance(const mavlink_message_t* msg, float *covariance) -{ - return _MAV_RETURN_float_array(msg, covariance, 45, 44); -} - -/** - * @brief Decode a local_position_ned_cov message into a struct - * - * @param msg The message to decode - * @param local_position_ned_cov C-struct to decode the message contents into - */ -static inline void mavlink_msg_local_position_ned_cov_decode(const mavlink_message_t* msg, mavlink_local_position_ned_cov_t* local_position_ned_cov) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - local_position_ned_cov->time_usec = mavlink_msg_local_position_ned_cov_get_time_usec(msg); - local_position_ned_cov->x = mavlink_msg_local_position_ned_cov_get_x(msg); - local_position_ned_cov->y = mavlink_msg_local_position_ned_cov_get_y(msg); - local_position_ned_cov->z = mavlink_msg_local_position_ned_cov_get_z(msg); - local_position_ned_cov->vx = mavlink_msg_local_position_ned_cov_get_vx(msg); - local_position_ned_cov->vy = mavlink_msg_local_position_ned_cov_get_vy(msg); - local_position_ned_cov->vz = mavlink_msg_local_position_ned_cov_get_vz(msg); - local_position_ned_cov->ax = mavlink_msg_local_position_ned_cov_get_ax(msg); - local_position_ned_cov->ay = mavlink_msg_local_position_ned_cov_get_ay(msg); - local_position_ned_cov->az = mavlink_msg_local_position_ned_cov_get_az(msg); - mavlink_msg_local_position_ned_cov_get_covariance(msg, local_position_ned_cov->covariance); - local_position_ned_cov->estimator_type = mavlink_msg_local_position_ned_cov_get_estimator_type(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN? msg->len : MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN; - memset(local_position_ned_cov, 0, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN); - memcpy(local_position_ned_cov, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_local_position_ned_system_global_offset.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_local_position_ned_system_global_offset.h deleted file mode 100644 index 30fbab19..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_local_position_ned_system_global_offset.h +++ /dev/null @@ -1,363 +0,0 @@ -#pragma once -// MESSAGE LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET PACKING - -#define MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET 89 - - -typedef struct __mavlink_local_position_ned_system_global_offset_t { - uint32_t time_boot_ms; /*< [ms] Timestamp (time since system boot).*/ - float x; /*< [m] X Position*/ - float y; /*< [m] Y Position*/ - float z; /*< [m] Z Position*/ - float roll; /*< [rad] Roll*/ - float pitch; /*< [rad] Pitch*/ - float yaw; /*< [rad] Yaw*/ -} mavlink_local_position_ned_system_global_offset_t; - -#define MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN 28 -#define MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_MIN_LEN 28 -#define MAVLINK_MSG_ID_89_LEN 28 -#define MAVLINK_MSG_ID_89_MIN_LEN 28 - -#define MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_CRC 231 -#define MAVLINK_MSG_ID_89_CRC 231 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET { \ - 89, \ - "LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET", \ - 7, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_local_position_ned_system_global_offset_t, time_boot_ms) }, \ - { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_local_position_ned_system_global_offset_t, x) }, \ - { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_local_position_ned_system_global_offset_t, y) }, \ - { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_local_position_ned_system_global_offset_t, z) }, \ - { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_local_position_ned_system_global_offset_t, roll) }, \ - { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_local_position_ned_system_global_offset_t, pitch) }, \ - { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_local_position_ned_system_global_offset_t, yaw) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET { \ - "LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET", \ - 7, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_local_position_ned_system_global_offset_t, time_boot_ms) }, \ - { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_local_position_ned_system_global_offset_t, x) }, \ - { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_local_position_ned_system_global_offset_t, y) }, \ - { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_local_position_ned_system_global_offset_t, z) }, \ - { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_local_position_ned_system_global_offset_t, roll) }, \ - { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_local_position_ned_system_global_offset_t, pitch) }, \ - { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_local_position_ned_system_global_offset_t, yaw) }, \ - } \ -} -#endif - -/** - * @brief Pack a local_position_ned_system_global_offset message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param time_boot_ms [ms] Timestamp (time since system boot). - * @param x [m] X Position - * @param y [m] Y Position - * @param z [m] Z Position - * @param roll [rad] Roll - * @param pitch [rad] Pitch - * @param yaw [rad] Yaw - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_local_position_ned_system_global_offset_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint32_t time_boot_ms, float x, float y, float z, float roll, float pitch, float yaw) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, x); - _mav_put_float(buf, 8, y); - _mav_put_float(buf, 12, z); - _mav_put_float(buf, 16, roll); - _mav_put_float(buf, 20, pitch); - _mav_put_float(buf, 24, yaw); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN); -#else - mavlink_local_position_ned_system_global_offset_t packet; - packet.time_boot_ms = time_boot_ms; - packet.x = x; - packet.y = y; - packet.z = z; - packet.roll = roll; - packet.pitch = pitch; - packet.yaw = yaw; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_MIN_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_CRC); -} - -/** - * @brief Pack a local_position_ned_system_global_offset message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_boot_ms [ms] Timestamp (time since system boot). - * @param x [m] X Position - * @param y [m] Y Position - * @param z [m] Z Position - * @param roll [rad] Roll - * @param pitch [rad] Pitch - * @param yaw [rad] Yaw - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_local_position_ned_system_global_offset_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint32_t time_boot_ms,float x,float y,float z,float roll,float pitch,float yaw) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, x); - _mav_put_float(buf, 8, y); - _mav_put_float(buf, 12, z); - _mav_put_float(buf, 16, roll); - _mav_put_float(buf, 20, pitch); - _mav_put_float(buf, 24, yaw); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN); -#else - mavlink_local_position_ned_system_global_offset_t packet; - packet.time_boot_ms = time_boot_ms; - packet.x = x; - packet.y = y; - packet.z = z; - packet.roll = roll; - packet.pitch = pitch; - packet.yaw = yaw; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_MIN_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_CRC); -} - -/** - * @brief Encode a local_position_ned_system_global_offset struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param local_position_ned_system_global_offset C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_local_position_ned_system_global_offset_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_local_position_ned_system_global_offset_t* local_position_ned_system_global_offset) -{ - return mavlink_msg_local_position_ned_system_global_offset_pack(system_id, component_id, msg, local_position_ned_system_global_offset->time_boot_ms, local_position_ned_system_global_offset->x, local_position_ned_system_global_offset->y, local_position_ned_system_global_offset->z, local_position_ned_system_global_offset->roll, local_position_ned_system_global_offset->pitch, local_position_ned_system_global_offset->yaw); -} - -/** - * @brief Encode a local_position_ned_system_global_offset struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param local_position_ned_system_global_offset C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_local_position_ned_system_global_offset_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_local_position_ned_system_global_offset_t* local_position_ned_system_global_offset) -{ - return mavlink_msg_local_position_ned_system_global_offset_pack_chan(system_id, component_id, chan, msg, local_position_ned_system_global_offset->time_boot_ms, local_position_ned_system_global_offset->x, local_position_ned_system_global_offset->y, local_position_ned_system_global_offset->z, local_position_ned_system_global_offset->roll, local_position_ned_system_global_offset->pitch, local_position_ned_system_global_offset->yaw); -} - -/** - * @brief Send a local_position_ned_system_global_offset message - * @param chan MAVLink channel to send the message - * - * @param time_boot_ms [ms] Timestamp (time since system boot). - * @param x [m] X Position - * @param y [m] Y Position - * @param z [m] Z Position - * @param roll [rad] Roll - * @param pitch [rad] Pitch - * @param yaw [rad] Yaw - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_local_position_ned_system_global_offset_send(mavlink_channel_t chan, uint32_t time_boot_ms, float x, float y, float z, float roll, float pitch, float yaw) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, x); - _mav_put_float(buf, 8, y); - _mav_put_float(buf, 12, z); - _mav_put_float(buf, 16, roll); - _mav_put_float(buf, 20, pitch); - _mav_put_float(buf, 24, yaw); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET, buf, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_MIN_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_CRC); -#else - mavlink_local_position_ned_system_global_offset_t packet; - packet.time_boot_ms = time_boot_ms; - packet.x = x; - packet.y = y; - packet.z = z; - packet.roll = roll; - packet.pitch = pitch; - packet.yaw = yaw; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET, (const char *)&packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_MIN_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_CRC); -#endif -} - -/** - * @brief Send a local_position_ned_system_global_offset message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_local_position_ned_system_global_offset_send_struct(mavlink_channel_t chan, const mavlink_local_position_ned_system_global_offset_t* local_position_ned_system_global_offset) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_local_position_ned_system_global_offset_send(chan, local_position_ned_system_global_offset->time_boot_ms, local_position_ned_system_global_offset->x, local_position_ned_system_global_offset->y, local_position_ned_system_global_offset->z, local_position_ned_system_global_offset->roll, local_position_ned_system_global_offset->pitch, local_position_ned_system_global_offset->yaw); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET, (const char *)local_position_ned_system_global_offset, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_MIN_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_CRC); -#endif -} - -#if MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_local_position_ned_system_global_offset_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, float x, float y, float z, float roll, float pitch, float yaw) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, x); - _mav_put_float(buf, 8, y); - _mav_put_float(buf, 12, z); - _mav_put_float(buf, 16, roll); - _mav_put_float(buf, 20, pitch); - _mav_put_float(buf, 24, yaw); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET, buf, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_MIN_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_CRC); -#else - mavlink_local_position_ned_system_global_offset_t *packet = (mavlink_local_position_ned_system_global_offset_t *)msgbuf; - packet->time_boot_ms = time_boot_ms; - packet->x = x; - packet->y = y; - packet->z = z; - packet->roll = roll; - packet->pitch = pitch; - packet->yaw = yaw; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET, (const char *)packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_MIN_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_CRC); -#endif -} -#endif - -#endif - -// MESSAGE LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET UNPACKING - - -/** - * @brief Get field time_boot_ms from local_position_ned_system_global_offset message - * - * @return [ms] Timestamp (time since system boot). - */ -static inline uint32_t mavlink_msg_local_position_ned_system_global_offset_get_time_boot_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field x from local_position_ned_system_global_offset message - * - * @return [m] X Position - */ -static inline float mavlink_msg_local_position_ned_system_global_offset_get_x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 4); -} - -/** - * @brief Get field y from local_position_ned_system_global_offset message - * - * @return [m] Y Position - */ -static inline float mavlink_msg_local_position_ned_system_global_offset_get_y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field z from local_position_ned_system_global_offset message - * - * @return [m] Z Position - */ -static inline float mavlink_msg_local_position_ned_system_global_offset_get_z(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field roll from local_position_ned_system_global_offset message - * - * @return [rad] Roll - */ -static inline float mavlink_msg_local_position_ned_system_global_offset_get_roll(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field pitch from local_position_ned_system_global_offset message - * - * @return [rad] Pitch - */ -static inline float mavlink_msg_local_position_ned_system_global_offset_get_pitch(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Get field yaw from local_position_ned_system_global_offset message - * - * @return [rad] Yaw - */ -static inline float mavlink_msg_local_position_ned_system_global_offset_get_yaw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Decode a local_position_ned_system_global_offset message into a struct - * - * @param msg The message to decode - * @param local_position_ned_system_global_offset C-struct to decode the message contents into - */ -static inline void mavlink_msg_local_position_ned_system_global_offset_decode(const mavlink_message_t* msg, mavlink_local_position_ned_system_global_offset_t* local_position_ned_system_global_offset) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - local_position_ned_system_global_offset->time_boot_ms = mavlink_msg_local_position_ned_system_global_offset_get_time_boot_ms(msg); - local_position_ned_system_global_offset->x = mavlink_msg_local_position_ned_system_global_offset_get_x(msg); - local_position_ned_system_global_offset->y = mavlink_msg_local_position_ned_system_global_offset_get_y(msg); - local_position_ned_system_global_offset->z = mavlink_msg_local_position_ned_system_global_offset_get_z(msg); - local_position_ned_system_global_offset->roll = mavlink_msg_local_position_ned_system_global_offset_get_roll(msg); - local_position_ned_system_global_offset->pitch = mavlink_msg_local_position_ned_system_global_offset_get_pitch(msg); - local_position_ned_system_global_offset->yaw = mavlink_msg_local_position_ned_system_global_offset_get_yaw(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN? msg->len : MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN; - memset(local_position_ned_system_global_offset, 0, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN); - memcpy(local_position_ned_system_global_offset, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_log_data.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_log_data.h deleted file mode 100644 index 6f879cd2..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_log_data.h +++ /dev/null @@ -1,280 +0,0 @@ -#pragma once -// MESSAGE LOG_DATA PACKING - -#define MAVLINK_MSG_ID_LOG_DATA 120 - - -typedef struct __mavlink_log_data_t { - uint32_t ofs; /*< Offset into the log*/ - uint16_t id; /*< Log id (from LOG_ENTRY reply)*/ - uint8_t count; /*< [bytes] Number of bytes (zero for end of log)*/ - uint8_t data[90]; /*< log data*/ -} mavlink_log_data_t; - -#define MAVLINK_MSG_ID_LOG_DATA_LEN 97 -#define MAVLINK_MSG_ID_LOG_DATA_MIN_LEN 97 -#define MAVLINK_MSG_ID_120_LEN 97 -#define MAVLINK_MSG_ID_120_MIN_LEN 97 - -#define MAVLINK_MSG_ID_LOG_DATA_CRC 134 -#define MAVLINK_MSG_ID_120_CRC 134 - -#define MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN 90 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_LOG_DATA { \ - 120, \ - "LOG_DATA", \ - 4, \ - { { "id", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_log_data_t, id) }, \ - { "ofs", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_log_data_t, ofs) }, \ - { "count", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_log_data_t, count) }, \ - { "data", NULL, MAVLINK_TYPE_UINT8_T, 90, 7, offsetof(mavlink_log_data_t, data) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_LOG_DATA { \ - "LOG_DATA", \ - 4, \ - { { "id", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_log_data_t, id) }, \ - { "ofs", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_log_data_t, ofs) }, \ - { "count", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_log_data_t, count) }, \ - { "data", NULL, MAVLINK_TYPE_UINT8_T, 90, 7, offsetof(mavlink_log_data_t, data) }, \ - } \ -} -#endif - -/** - * @brief Pack a log_data message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param id Log id (from LOG_ENTRY reply) - * @param ofs Offset into the log - * @param count [bytes] Number of bytes (zero for end of log) - * @param data log data - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_log_data_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint16_t id, uint32_t ofs, uint8_t count, const uint8_t *data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LOG_DATA_LEN]; - _mav_put_uint32_t(buf, 0, ofs); - _mav_put_uint16_t(buf, 4, id); - _mav_put_uint8_t(buf, 6, count); - _mav_put_uint8_t_array(buf, 7, data, 90); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOG_DATA_LEN); -#else - mavlink_log_data_t packet; - packet.ofs = ofs; - packet.id = id; - packet.count = count; - mav_array_memcpy(packet.data, data, sizeof(uint8_t)*90); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOG_DATA_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_LOG_DATA; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOG_DATA_MIN_LEN, MAVLINK_MSG_ID_LOG_DATA_LEN, MAVLINK_MSG_ID_LOG_DATA_CRC); -} - -/** - * @brief Pack a log_data message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param id Log id (from LOG_ENTRY reply) - * @param ofs Offset into the log - * @param count [bytes] Number of bytes (zero for end of log) - * @param data log data - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_log_data_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint16_t id,uint32_t ofs,uint8_t count,const uint8_t *data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LOG_DATA_LEN]; - _mav_put_uint32_t(buf, 0, ofs); - _mav_put_uint16_t(buf, 4, id); - _mav_put_uint8_t(buf, 6, count); - _mav_put_uint8_t_array(buf, 7, data, 90); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOG_DATA_LEN); -#else - mavlink_log_data_t packet; - packet.ofs = ofs; - packet.id = id; - packet.count = count; - mav_array_memcpy(packet.data, data, sizeof(uint8_t)*90); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOG_DATA_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_LOG_DATA; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOG_DATA_MIN_LEN, MAVLINK_MSG_ID_LOG_DATA_LEN, MAVLINK_MSG_ID_LOG_DATA_CRC); -} - -/** - * @brief Encode a log_data struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param log_data C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_log_data_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_log_data_t* log_data) -{ - return mavlink_msg_log_data_pack(system_id, component_id, msg, log_data->id, log_data->ofs, log_data->count, log_data->data); -} - -/** - * @brief Encode a log_data struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param log_data C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_log_data_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_log_data_t* log_data) -{ - return mavlink_msg_log_data_pack_chan(system_id, component_id, chan, msg, log_data->id, log_data->ofs, log_data->count, log_data->data); -} - -/** - * @brief Send a log_data message - * @param chan MAVLink channel to send the message - * - * @param id Log id (from LOG_ENTRY reply) - * @param ofs Offset into the log - * @param count [bytes] Number of bytes (zero for end of log) - * @param data log data - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_log_data_send(mavlink_channel_t chan, uint16_t id, uint32_t ofs, uint8_t count, const uint8_t *data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LOG_DATA_LEN]; - _mav_put_uint32_t(buf, 0, ofs); - _mav_put_uint16_t(buf, 4, id); - _mav_put_uint8_t(buf, 6, count); - _mav_put_uint8_t_array(buf, 7, data, 90); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_DATA, buf, MAVLINK_MSG_ID_LOG_DATA_MIN_LEN, MAVLINK_MSG_ID_LOG_DATA_LEN, MAVLINK_MSG_ID_LOG_DATA_CRC); -#else - mavlink_log_data_t packet; - packet.ofs = ofs; - packet.id = id; - packet.count = count; - mav_array_memcpy(packet.data, data, sizeof(uint8_t)*90); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_DATA, (const char *)&packet, MAVLINK_MSG_ID_LOG_DATA_MIN_LEN, MAVLINK_MSG_ID_LOG_DATA_LEN, MAVLINK_MSG_ID_LOG_DATA_CRC); -#endif -} - -/** - * @brief Send a log_data message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_log_data_send_struct(mavlink_channel_t chan, const mavlink_log_data_t* log_data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_log_data_send(chan, log_data->id, log_data->ofs, log_data->count, log_data->data); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_DATA, (const char *)log_data, MAVLINK_MSG_ID_LOG_DATA_MIN_LEN, MAVLINK_MSG_ID_LOG_DATA_LEN, MAVLINK_MSG_ID_LOG_DATA_CRC); -#endif -} - -#if MAVLINK_MSG_ID_LOG_DATA_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_log_data_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint16_t id, uint32_t ofs, uint8_t count, const uint8_t *data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, ofs); - _mav_put_uint16_t(buf, 4, id); - _mav_put_uint8_t(buf, 6, count); - _mav_put_uint8_t_array(buf, 7, data, 90); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_DATA, buf, MAVLINK_MSG_ID_LOG_DATA_MIN_LEN, MAVLINK_MSG_ID_LOG_DATA_LEN, MAVLINK_MSG_ID_LOG_DATA_CRC); -#else - mavlink_log_data_t *packet = (mavlink_log_data_t *)msgbuf; - packet->ofs = ofs; - packet->id = id; - packet->count = count; - mav_array_memcpy(packet->data, data, sizeof(uint8_t)*90); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_DATA, (const char *)packet, MAVLINK_MSG_ID_LOG_DATA_MIN_LEN, MAVLINK_MSG_ID_LOG_DATA_LEN, MAVLINK_MSG_ID_LOG_DATA_CRC); -#endif -} -#endif - -#endif - -// MESSAGE LOG_DATA UNPACKING - - -/** - * @brief Get field id from log_data message - * - * @return Log id (from LOG_ENTRY reply) - */ -static inline uint16_t mavlink_msg_log_data_get_id(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 4); -} - -/** - * @brief Get field ofs from log_data message - * - * @return Offset into the log - */ -static inline uint32_t mavlink_msg_log_data_get_ofs(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field count from log_data message - * - * @return [bytes] Number of bytes (zero for end of log) - */ -static inline uint8_t mavlink_msg_log_data_get_count(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 6); -} - -/** - * @brief Get field data from log_data message - * - * @return log data - */ -static inline uint16_t mavlink_msg_log_data_get_data(const mavlink_message_t* msg, uint8_t *data) -{ - return _MAV_RETURN_uint8_t_array(msg, data, 90, 7); -} - -/** - * @brief Decode a log_data message into a struct - * - * @param msg The message to decode - * @param log_data C-struct to decode the message contents into - */ -static inline void mavlink_msg_log_data_decode(const mavlink_message_t* msg, mavlink_log_data_t* log_data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - log_data->ofs = mavlink_msg_log_data_get_ofs(msg); - log_data->id = mavlink_msg_log_data_get_id(msg); - log_data->count = mavlink_msg_log_data_get_count(msg); - mavlink_msg_log_data_get_data(msg, log_data->data); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_LOG_DATA_LEN? msg->len : MAVLINK_MSG_ID_LOG_DATA_LEN; - memset(log_data, 0, MAVLINK_MSG_ID_LOG_DATA_LEN); - memcpy(log_data, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_log_entry.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_log_entry.h deleted file mode 100644 index 6fb0048a..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_log_entry.h +++ /dev/null @@ -1,313 +0,0 @@ -#pragma once -// MESSAGE LOG_ENTRY PACKING - -#define MAVLINK_MSG_ID_LOG_ENTRY 118 - - -typedef struct __mavlink_log_entry_t { - uint32_t time_utc; /*< [s] UTC timestamp of log since 1970, or 0 if not available*/ - uint32_t size; /*< [bytes] Size of the log (may be approximate)*/ - uint16_t id; /*< Log id*/ - uint16_t num_logs; /*< Total number of logs*/ - uint16_t last_log_num; /*< High log number*/ -} mavlink_log_entry_t; - -#define MAVLINK_MSG_ID_LOG_ENTRY_LEN 14 -#define MAVLINK_MSG_ID_LOG_ENTRY_MIN_LEN 14 -#define MAVLINK_MSG_ID_118_LEN 14 -#define MAVLINK_MSG_ID_118_MIN_LEN 14 - -#define MAVLINK_MSG_ID_LOG_ENTRY_CRC 56 -#define MAVLINK_MSG_ID_118_CRC 56 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_LOG_ENTRY { \ - 118, \ - "LOG_ENTRY", \ - 5, \ - { { "id", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_log_entry_t, id) }, \ - { "num_logs", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_log_entry_t, num_logs) }, \ - { "last_log_num", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_log_entry_t, last_log_num) }, \ - { "time_utc", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_log_entry_t, time_utc) }, \ - { "size", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_log_entry_t, size) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_LOG_ENTRY { \ - "LOG_ENTRY", \ - 5, \ - { { "id", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_log_entry_t, id) }, \ - { "num_logs", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_log_entry_t, num_logs) }, \ - { "last_log_num", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_log_entry_t, last_log_num) }, \ - { "time_utc", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_log_entry_t, time_utc) }, \ - { "size", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_log_entry_t, size) }, \ - } \ -} -#endif - -/** - * @brief Pack a log_entry message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param id Log id - * @param num_logs Total number of logs - * @param last_log_num High log number - * @param time_utc [s] UTC timestamp of log since 1970, or 0 if not available - * @param size [bytes] Size of the log (may be approximate) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_log_entry_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint16_t id, uint16_t num_logs, uint16_t last_log_num, uint32_t time_utc, uint32_t size) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LOG_ENTRY_LEN]; - _mav_put_uint32_t(buf, 0, time_utc); - _mav_put_uint32_t(buf, 4, size); - _mav_put_uint16_t(buf, 8, id); - _mav_put_uint16_t(buf, 10, num_logs); - _mav_put_uint16_t(buf, 12, last_log_num); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOG_ENTRY_LEN); -#else - mavlink_log_entry_t packet; - packet.time_utc = time_utc; - packet.size = size; - packet.id = id; - packet.num_logs = num_logs; - packet.last_log_num = last_log_num; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOG_ENTRY_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_LOG_ENTRY; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOG_ENTRY_MIN_LEN, MAVLINK_MSG_ID_LOG_ENTRY_LEN, MAVLINK_MSG_ID_LOG_ENTRY_CRC); -} - -/** - * @brief Pack a log_entry message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param id Log id - * @param num_logs Total number of logs - * @param last_log_num High log number - * @param time_utc [s] UTC timestamp of log since 1970, or 0 if not available - * @param size [bytes] Size of the log (may be approximate) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_log_entry_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint16_t id,uint16_t num_logs,uint16_t last_log_num,uint32_t time_utc,uint32_t size) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LOG_ENTRY_LEN]; - _mav_put_uint32_t(buf, 0, time_utc); - _mav_put_uint32_t(buf, 4, size); - _mav_put_uint16_t(buf, 8, id); - _mav_put_uint16_t(buf, 10, num_logs); - _mav_put_uint16_t(buf, 12, last_log_num); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOG_ENTRY_LEN); -#else - mavlink_log_entry_t packet; - packet.time_utc = time_utc; - packet.size = size; - packet.id = id; - packet.num_logs = num_logs; - packet.last_log_num = last_log_num; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOG_ENTRY_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_LOG_ENTRY; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOG_ENTRY_MIN_LEN, MAVLINK_MSG_ID_LOG_ENTRY_LEN, MAVLINK_MSG_ID_LOG_ENTRY_CRC); -} - -/** - * @brief Encode a log_entry struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param log_entry C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_log_entry_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_log_entry_t* log_entry) -{ - return mavlink_msg_log_entry_pack(system_id, component_id, msg, log_entry->id, log_entry->num_logs, log_entry->last_log_num, log_entry->time_utc, log_entry->size); -} - -/** - * @brief Encode a log_entry struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param log_entry C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_log_entry_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_log_entry_t* log_entry) -{ - return mavlink_msg_log_entry_pack_chan(system_id, component_id, chan, msg, log_entry->id, log_entry->num_logs, log_entry->last_log_num, log_entry->time_utc, log_entry->size); -} - -/** - * @brief Send a log_entry message - * @param chan MAVLink channel to send the message - * - * @param id Log id - * @param num_logs Total number of logs - * @param last_log_num High log number - * @param time_utc [s] UTC timestamp of log since 1970, or 0 if not available - * @param size [bytes] Size of the log (may be approximate) - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_log_entry_send(mavlink_channel_t chan, uint16_t id, uint16_t num_logs, uint16_t last_log_num, uint32_t time_utc, uint32_t size) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LOG_ENTRY_LEN]; - _mav_put_uint32_t(buf, 0, time_utc); - _mav_put_uint32_t(buf, 4, size); - _mav_put_uint16_t(buf, 8, id); - _mav_put_uint16_t(buf, 10, num_logs); - _mav_put_uint16_t(buf, 12, last_log_num); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_ENTRY, buf, MAVLINK_MSG_ID_LOG_ENTRY_MIN_LEN, MAVLINK_MSG_ID_LOG_ENTRY_LEN, MAVLINK_MSG_ID_LOG_ENTRY_CRC); -#else - mavlink_log_entry_t packet; - packet.time_utc = time_utc; - packet.size = size; - packet.id = id; - packet.num_logs = num_logs; - packet.last_log_num = last_log_num; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_ENTRY, (const char *)&packet, MAVLINK_MSG_ID_LOG_ENTRY_MIN_LEN, MAVLINK_MSG_ID_LOG_ENTRY_LEN, MAVLINK_MSG_ID_LOG_ENTRY_CRC); -#endif -} - -/** - * @brief Send a log_entry message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_log_entry_send_struct(mavlink_channel_t chan, const mavlink_log_entry_t* log_entry) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_log_entry_send(chan, log_entry->id, log_entry->num_logs, log_entry->last_log_num, log_entry->time_utc, log_entry->size); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_ENTRY, (const char *)log_entry, MAVLINK_MSG_ID_LOG_ENTRY_MIN_LEN, MAVLINK_MSG_ID_LOG_ENTRY_LEN, MAVLINK_MSG_ID_LOG_ENTRY_CRC); -#endif -} - -#if MAVLINK_MSG_ID_LOG_ENTRY_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_log_entry_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint16_t id, uint16_t num_logs, uint16_t last_log_num, uint32_t time_utc, uint32_t size) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, time_utc); - _mav_put_uint32_t(buf, 4, size); - _mav_put_uint16_t(buf, 8, id); - _mav_put_uint16_t(buf, 10, num_logs); - _mav_put_uint16_t(buf, 12, last_log_num); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_ENTRY, buf, MAVLINK_MSG_ID_LOG_ENTRY_MIN_LEN, MAVLINK_MSG_ID_LOG_ENTRY_LEN, MAVLINK_MSG_ID_LOG_ENTRY_CRC); -#else - mavlink_log_entry_t *packet = (mavlink_log_entry_t *)msgbuf; - packet->time_utc = time_utc; - packet->size = size; - packet->id = id; - packet->num_logs = num_logs; - packet->last_log_num = last_log_num; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_ENTRY, (const char *)packet, MAVLINK_MSG_ID_LOG_ENTRY_MIN_LEN, MAVLINK_MSG_ID_LOG_ENTRY_LEN, MAVLINK_MSG_ID_LOG_ENTRY_CRC); -#endif -} -#endif - -#endif - -// MESSAGE LOG_ENTRY UNPACKING - - -/** - * @brief Get field id from log_entry message - * - * @return Log id - */ -static inline uint16_t mavlink_msg_log_entry_get_id(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 8); -} - -/** - * @brief Get field num_logs from log_entry message - * - * @return Total number of logs - */ -static inline uint16_t mavlink_msg_log_entry_get_num_logs(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 10); -} - -/** - * @brief Get field last_log_num from log_entry message - * - * @return High log number - */ -static inline uint16_t mavlink_msg_log_entry_get_last_log_num(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 12); -} - -/** - * @brief Get field time_utc from log_entry message - * - * @return [s] UTC timestamp of log since 1970, or 0 if not available - */ -static inline uint32_t mavlink_msg_log_entry_get_time_utc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field size from log_entry message - * - * @return [bytes] Size of the log (may be approximate) - */ -static inline uint32_t mavlink_msg_log_entry_get_size(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 4); -} - -/** - * @brief Decode a log_entry message into a struct - * - * @param msg The message to decode - * @param log_entry C-struct to decode the message contents into - */ -static inline void mavlink_msg_log_entry_decode(const mavlink_message_t* msg, mavlink_log_entry_t* log_entry) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - log_entry->time_utc = mavlink_msg_log_entry_get_time_utc(msg); - log_entry->size = mavlink_msg_log_entry_get_size(msg); - log_entry->id = mavlink_msg_log_entry_get_id(msg); - log_entry->num_logs = mavlink_msg_log_entry_get_num_logs(msg); - log_entry->last_log_num = mavlink_msg_log_entry_get_last_log_num(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_LOG_ENTRY_LEN? msg->len : MAVLINK_MSG_ID_LOG_ENTRY_LEN; - memset(log_entry, 0, MAVLINK_MSG_ID_LOG_ENTRY_LEN); - memcpy(log_entry, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_log_erase.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_log_erase.h deleted file mode 100644 index 1dec9e29..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_log_erase.h +++ /dev/null @@ -1,238 +0,0 @@ -#pragma once -// MESSAGE LOG_ERASE PACKING - -#define MAVLINK_MSG_ID_LOG_ERASE 121 - - -typedef struct __mavlink_log_erase_t { - uint8_t target_system; /*< System ID*/ - uint8_t target_component; /*< Component ID*/ -} mavlink_log_erase_t; - -#define MAVLINK_MSG_ID_LOG_ERASE_LEN 2 -#define MAVLINK_MSG_ID_LOG_ERASE_MIN_LEN 2 -#define MAVLINK_MSG_ID_121_LEN 2 -#define MAVLINK_MSG_ID_121_MIN_LEN 2 - -#define MAVLINK_MSG_ID_LOG_ERASE_CRC 237 -#define MAVLINK_MSG_ID_121_CRC 237 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_LOG_ERASE { \ - 121, \ - "LOG_ERASE", \ - 2, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_log_erase_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_log_erase_t, target_component) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_LOG_ERASE { \ - "LOG_ERASE", \ - 2, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_log_erase_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_log_erase_t, target_component) }, \ - } \ -} -#endif - -/** - * @brief Pack a log_erase message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID - * @param target_component Component ID - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_log_erase_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LOG_ERASE_LEN]; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOG_ERASE_LEN); -#else - mavlink_log_erase_t packet; - packet.target_system = target_system; - packet.target_component = target_component; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOG_ERASE_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_LOG_ERASE; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOG_ERASE_MIN_LEN, MAVLINK_MSG_ID_LOG_ERASE_LEN, MAVLINK_MSG_ID_LOG_ERASE_CRC); -} - -/** - * @brief Pack a log_erase message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_log_erase_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LOG_ERASE_LEN]; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOG_ERASE_LEN); -#else - mavlink_log_erase_t packet; - packet.target_system = target_system; - packet.target_component = target_component; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOG_ERASE_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_LOG_ERASE; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOG_ERASE_MIN_LEN, MAVLINK_MSG_ID_LOG_ERASE_LEN, MAVLINK_MSG_ID_LOG_ERASE_CRC); -} - -/** - * @brief Encode a log_erase struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param log_erase C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_log_erase_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_log_erase_t* log_erase) -{ - return mavlink_msg_log_erase_pack(system_id, component_id, msg, log_erase->target_system, log_erase->target_component); -} - -/** - * @brief Encode a log_erase struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param log_erase C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_log_erase_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_log_erase_t* log_erase) -{ - return mavlink_msg_log_erase_pack_chan(system_id, component_id, chan, msg, log_erase->target_system, log_erase->target_component); -} - -/** - * @brief Send a log_erase message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param target_component Component ID - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_log_erase_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LOG_ERASE_LEN]; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_ERASE, buf, MAVLINK_MSG_ID_LOG_ERASE_MIN_LEN, MAVLINK_MSG_ID_LOG_ERASE_LEN, MAVLINK_MSG_ID_LOG_ERASE_CRC); -#else - mavlink_log_erase_t packet; - packet.target_system = target_system; - packet.target_component = target_component; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_ERASE, (const char *)&packet, MAVLINK_MSG_ID_LOG_ERASE_MIN_LEN, MAVLINK_MSG_ID_LOG_ERASE_LEN, MAVLINK_MSG_ID_LOG_ERASE_CRC); -#endif -} - -/** - * @brief Send a log_erase message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_log_erase_send_struct(mavlink_channel_t chan, const mavlink_log_erase_t* log_erase) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_log_erase_send(chan, log_erase->target_system, log_erase->target_component); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_ERASE, (const char *)log_erase, MAVLINK_MSG_ID_LOG_ERASE_MIN_LEN, MAVLINK_MSG_ID_LOG_ERASE_LEN, MAVLINK_MSG_ID_LOG_ERASE_CRC); -#endif -} - -#if MAVLINK_MSG_ID_LOG_ERASE_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_log_erase_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_ERASE, buf, MAVLINK_MSG_ID_LOG_ERASE_MIN_LEN, MAVLINK_MSG_ID_LOG_ERASE_LEN, MAVLINK_MSG_ID_LOG_ERASE_CRC); -#else - mavlink_log_erase_t *packet = (mavlink_log_erase_t *)msgbuf; - packet->target_system = target_system; - packet->target_component = target_component; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_ERASE, (const char *)packet, MAVLINK_MSG_ID_LOG_ERASE_MIN_LEN, MAVLINK_MSG_ID_LOG_ERASE_LEN, MAVLINK_MSG_ID_LOG_ERASE_CRC); -#endif -} -#endif - -#endif - -// MESSAGE LOG_ERASE UNPACKING - - -/** - * @brief Get field target_system from log_erase message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_log_erase_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 0); -} - -/** - * @brief Get field target_component from log_erase message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_log_erase_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 1); -} - -/** - * @brief Decode a log_erase message into a struct - * - * @param msg The message to decode - * @param log_erase C-struct to decode the message contents into - */ -static inline void mavlink_msg_log_erase_decode(const mavlink_message_t* msg, mavlink_log_erase_t* log_erase) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - log_erase->target_system = mavlink_msg_log_erase_get_target_system(msg); - log_erase->target_component = mavlink_msg_log_erase_get_target_component(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_LOG_ERASE_LEN? msg->len : MAVLINK_MSG_ID_LOG_ERASE_LEN; - memset(log_erase, 0, MAVLINK_MSG_ID_LOG_ERASE_LEN); - memcpy(log_erase, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_log_request_data.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_log_request_data.h deleted file mode 100644 index 6cc0cfb7..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_log_request_data.h +++ /dev/null @@ -1,313 +0,0 @@ -#pragma once -// MESSAGE LOG_REQUEST_DATA PACKING - -#define MAVLINK_MSG_ID_LOG_REQUEST_DATA 119 - - -typedef struct __mavlink_log_request_data_t { - uint32_t ofs; /*< Offset into the log*/ - uint32_t count; /*< [bytes] Number of bytes*/ - uint16_t id; /*< Log id (from LOG_ENTRY reply)*/ - uint8_t target_system; /*< System ID*/ - uint8_t target_component; /*< Component ID*/ -} mavlink_log_request_data_t; - -#define MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN 12 -#define MAVLINK_MSG_ID_LOG_REQUEST_DATA_MIN_LEN 12 -#define MAVLINK_MSG_ID_119_LEN 12 -#define MAVLINK_MSG_ID_119_MIN_LEN 12 - -#define MAVLINK_MSG_ID_LOG_REQUEST_DATA_CRC 116 -#define MAVLINK_MSG_ID_119_CRC 116 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_LOG_REQUEST_DATA { \ - 119, \ - "LOG_REQUEST_DATA", \ - 5, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_log_request_data_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_log_request_data_t, target_component) }, \ - { "id", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_log_request_data_t, id) }, \ - { "ofs", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_log_request_data_t, ofs) }, \ - { "count", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_log_request_data_t, count) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_LOG_REQUEST_DATA { \ - "LOG_REQUEST_DATA", \ - 5, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_log_request_data_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_log_request_data_t, target_component) }, \ - { "id", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_log_request_data_t, id) }, \ - { "ofs", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_log_request_data_t, ofs) }, \ - { "count", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_log_request_data_t, count) }, \ - } \ -} -#endif - -/** - * @brief Pack a log_request_data message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID - * @param target_component Component ID - * @param id Log id (from LOG_ENTRY reply) - * @param ofs Offset into the log - * @param count [bytes] Number of bytes - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_log_request_data_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component, uint16_t id, uint32_t ofs, uint32_t count) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN]; - _mav_put_uint32_t(buf, 0, ofs); - _mav_put_uint32_t(buf, 4, count); - _mav_put_uint16_t(buf, 8, id); - _mav_put_uint8_t(buf, 10, target_system); - _mav_put_uint8_t(buf, 11, target_component); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN); -#else - mavlink_log_request_data_t packet; - packet.ofs = ofs; - packet.count = count; - packet.id = id; - packet.target_system = target_system; - packet.target_component = target_component; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_LOG_REQUEST_DATA; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOG_REQUEST_DATA_MIN_LEN, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN, MAVLINK_MSG_ID_LOG_REQUEST_DATA_CRC); -} - -/** - * @brief Pack a log_request_data message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @param id Log id (from LOG_ENTRY reply) - * @param ofs Offset into the log - * @param count [bytes] Number of bytes - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_log_request_data_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component,uint16_t id,uint32_t ofs,uint32_t count) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN]; - _mav_put_uint32_t(buf, 0, ofs); - _mav_put_uint32_t(buf, 4, count); - _mav_put_uint16_t(buf, 8, id); - _mav_put_uint8_t(buf, 10, target_system); - _mav_put_uint8_t(buf, 11, target_component); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN); -#else - mavlink_log_request_data_t packet; - packet.ofs = ofs; - packet.count = count; - packet.id = id; - packet.target_system = target_system; - packet.target_component = target_component; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_LOG_REQUEST_DATA; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOG_REQUEST_DATA_MIN_LEN, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN, MAVLINK_MSG_ID_LOG_REQUEST_DATA_CRC); -} - -/** - * @brief Encode a log_request_data struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param log_request_data C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_log_request_data_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_log_request_data_t* log_request_data) -{ - return mavlink_msg_log_request_data_pack(system_id, component_id, msg, log_request_data->target_system, log_request_data->target_component, log_request_data->id, log_request_data->ofs, log_request_data->count); -} - -/** - * @brief Encode a log_request_data struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param log_request_data C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_log_request_data_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_log_request_data_t* log_request_data) -{ - return mavlink_msg_log_request_data_pack_chan(system_id, component_id, chan, msg, log_request_data->target_system, log_request_data->target_component, log_request_data->id, log_request_data->ofs, log_request_data->count); -} - -/** - * @brief Send a log_request_data message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param target_component Component ID - * @param id Log id (from LOG_ENTRY reply) - * @param ofs Offset into the log - * @param count [bytes] Number of bytes - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_log_request_data_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t id, uint32_t ofs, uint32_t count) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN]; - _mav_put_uint32_t(buf, 0, ofs); - _mav_put_uint32_t(buf, 4, count); - _mav_put_uint16_t(buf, 8, id); - _mav_put_uint8_t(buf, 10, target_system); - _mav_put_uint8_t(buf, 11, target_component); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_DATA, buf, MAVLINK_MSG_ID_LOG_REQUEST_DATA_MIN_LEN, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN, MAVLINK_MSG_ID_LOG_REQUEST_DATA_CRC); -#else - mavlink_log_request_data_t packet; - packet.ofs = ofs; - packet.count = count; - packet.id = id; - packet.target_system = target_system; - packet.target_component = target_component; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_DATA, (const char *)&packet, MAVLINK_MSG_ID_LOG_REQUEST_DATA_MIN_LEN, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN, MAVLINK_MSG_ID_LOG_REQUEST_DATA_CRC); -#endif -} - -/** - * @brief Send a log_request_data message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_log_request_data_send_struct(mavlink_channel_t chan, const mavlink_log_request_data_t* log_request_data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_log_request_data_send(chan, log_request_data->target_system, log_request_data->target_component, log_request_data->id, log_request_data->ofs, log_request_data->count); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_DATA, (const char *)log_request_data, MAVLINK_MSG_ID_LOG_REQUEST_DATA_MIN_LEN, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN, MAVLINK_MSG_ID_LOG_REQUEST_DATA_CRC); -#endif -} - -#if MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_log_request_data_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t id, uint32_t ofs, uint32_t count) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, ofs); - _mav_put_uint32_t(buf, 4, count); - _mav_put_uint16_t(buf, 8, id); - _mav_put_uint8_t(buf, 10, target_system); - _mav_put_uint8_t(buf, 11, target_component); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_DATA, buf, MAVLINK_MSG_ID_LOG_REQUEST_DATA_MIN_LEN, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN, MAVLINK_MSG_ID_LOG_REQUEST_DATA_CRC); -#else - mavlink_log_request_data_t *packet = (mavlink_log_request_data_t *)msgbuf; - packet->ofs = ofs; - packet->count = count; - packet->id = id; - packet->target_system = target_system; - packet->target_component = target_component; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_DATA, (const char *)packet, MAVLINK_MSG_ID_LOG_REQUEST_DATA_MIN_LEN, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN, MAVLINK_MSG_ID_LOG_REQUEST_DATA_CRC); -#endif -} -#endif - -#endif - -// MESSAGE LOG_REQUEST_DATA UNPACKING - - -/** - * @brief Get field target_system from log_request_data message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_log_request_data_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 10); -} - -/** - * @brief Get field target_component from log_request_data message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_log_request_data_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 11); -} - -/** - * @brief Get field id from log_request_data message - * - * @return Log id (from LOG_ENTRY reply) - */ -static inline uint16_t mavlink_msg_log_request_data_get_id(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 8); -} - -/** - * @brief Get field ofs from log_request_data message - * - * @return Offset into the log - */ -static inline uint32_t mavlink_msg_log_request_data_get_ofs(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field count from log_request_data message - * - * @return [bytes] Number of bytes - */ -static inline uint32_t mavlink_msg_log_request_data_get_count(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 4); -} - -/** - * @brief Decode a log_request_data message into a struct - * - * @param msg The message to decode - * @param log_request_data C-struct to decode the message contents into - */ -static inline void mavlink_msg_log_request_data_decode(const mavlink_message_t* msg, mavlink_log_request_data_t* log_request_data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - log_request_data->ofs = mavlink_msg_log_request_data_get_ofs(msg); - log_request_data->count = mavlink_msg_log_request_data_get_count(msg); - log_request_data->id = mavlink_msg_log_request_data_get_id(msg); - log_request_data->target_system = mavlink_msg_log_request_data_get_target_system(msg); - log_request_data->target_component = mavlink_msg_log_request_data_get_target_component(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN? msg->len : MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN; - memset(log_request_data, 0, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN); - memcpy(log_request_data, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_log_request_end.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_log_request_end.h deleted file mode 100644 index 387a7c09..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_log_request_end.h +++ /dev/null @@ -1,238 +0,0 @@ -#pragma once -// MESSAGE LOG_REQUEST_END PACKING - -#define MAVLINK_MSG_ID_LOG_REQUEST_END 122 - - -typedef struct __mavlink_log_request_end_t { - uint8_t target_system; /*< System ID*/ - uint8_t target_component; /*< Component ID*/ -} mavlink_log_request_end_t; - -#define MAVLINK_MSG_ID_LOG_REQUEST_END_LEN 2 -#define MAVLINK_MSG_ID_LOG_REQUEST_END_MIN_LEN 2 -#define MAVLINK_MSG_ID_122_LEN 2 -#define MAVLINK_MSG_ID_122_MIN_LEN 2 - -#define MAVLINK_MSG_ID_LOG_REQUEST_END_CRC 203 -#define MAVLINK_MSG_ID_122_CRC 203 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_LOG_REQUEST_END { \ - 122, \ - "LOG_REQUEST_END", \ - 2, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_log_request_end_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_log_request_end_t, target_component) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_LOG_REQUEST_END { \ - "LOG_REQUEST_END", \ - 2, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_log_request_end_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_log_request_end_t, target_component) }, \ - } \ -} -#endif - -/** - * @brief Pack a log_request_end message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID - * @param target_component Component ID - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_log_request_end_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LOG_REQUEST_END_LEN]; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOG_REQUEST_END_LEN); -#else - mavlink_log_request_end_t packet; - packet.target_system = target_system; - packet.target_component = target_component; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOG_REQUEST_END_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_LOG_REQUEST_END; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOG_REQUEST_END_MIN_LEN, MAVLINK_MSG_ID_LOG_REQUEST_END_LEN, MAVLINK_MSG_ID_LOG_REQUEST_END_CRC); -} - -/** - * @brief Pack a log_request_end message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_log_request_end_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LOG_REQUEST_END_LEN]; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOG_REQUEST_END_LEN); -#else - mavlink_log_request_end_t packet; - packet.target_system = target_system; - packet.target_component = target_component; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOG_REQUEST_END_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_LOG_REQUEST_END; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOG_REQUEST_END_MIN_LEN, MAVLINK_MSG_ID_LOG_REQUEST_END_LEN, MAVLINK_MSG_ID_LOG_REQUEST_END_CRC); -} - -/** - * @brief Encode a log_request_end struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param log_request_end C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_log_request_end_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_log_request_end_t* log_request_end) -{ - return mavlink_msg_log_request_end_pack(system_id, component_id, msg, log_request_end->target_system, log_request_end->target_component); -} - -/** - * @brief Encode a log_request_end struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param log_request_end C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_log_request_end_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_log_request_end_t* log_request_end) -{ - return mavlink_msg_log_request_end_pack_chan(system_id, component_id, chan, msg, log_request_end->target_system, log_request_end->target_component); -} - -/** - * @brief Send a log_request_end message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param target_component Component ID - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_log_request_end_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LOG_REQUEST_END_LEN]; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_END, buf, MAVLINK_MSG_ID_LOG_REQUEST_END_MIN_LEN, MAVLINK_MSG_ID_LOG_REQUEST_END_LEN, MAVLINK_MSG_ID_LOG_REQUEST_END_CRC); -#else - mavlink_log_request_end_t packet; - packet.target_system = target_system; - packet.target_component = target_component; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_END, (const char *)&packet, MAVLINK_MSG_ID_LOG_REQUEST_END_MIN_LEN, MAVLINK_MSG_ID_LOG_REQUEST_END_LEN, MAVLINK_MSG_ID_LOG_REQUEST_END_CRC); -#endif -} - -/** - * @brief Send a log_request_end message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_log_request_end_send_struct(mavlink_channel_t chan, const mavlink_log_request_end_t* log_request_end) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_log_request_end_send(chan, log_request_end->target_system, log_request_end->target_component); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_END, (const char *)log_request_end, MAVLINK_MSG_ID_LOG_REQUEST_END_MIN_LEN, MAVLINK_MSG_ID_LOG_REQUEST_END_LEN, MAVLINK_MSG_ID_LOG_REQUEST_END_CRC); -#endif -} - -#if MAVLINK_MSG_ID_LOG_REQUEST_END_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_log_request_end_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_END, buf, MAVLINK_MSG_ID_LOG_REQUEST_END_MIN_LEN, MAVLINK_MSG_ID_LOG_REQUEST_END_LEN, MAVLINK_MSG_ID_LOG_REQUEST_END_CRC); -#else - mavlink_log_request_end_t *packet = (mavlink_log_request_end_t *)msgbuf; - packet->target_system = target_system; - packet->target_component = target_component; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_END, (const char *)packet, MAVLINK_MSG_ID_LOG_REQUEST_END_MIN_LEN, MAVLINK_MSG_ID_LOG_REQUEST_END_LEN, MAVLINK_MSG_ID_LOG_REQUEST_END_CRC); -#endif -} -#endif - -#endif - -// MESSAGE LOG_REQUEST_END UNPACKING - - -/** - * @brief Get field target_system from log_request_end message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_log_request_end_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 0); -} - -/** - * @brief Get field target_component from log_request_end message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_log_request_end_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 1); -} - -/** - * @brief Decode a log_request_end message into a struct - * - * @param msg The message to decode - * @param log_request_end C-struct to decode the message contents into - */ -static inline void mavlink_msg_log_request_end_decode(const mavlink_message_t* msg, mavlink_log_request_end_t* log_request_end) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - log_request_end->target_system = mavlink_msg_log_request_end_get_target_system(msg); - log_request_end->target_component = mavlink_msg_log_request_end_get_target_component(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_LOG_REQUEST_END_LEN? msg->len : MAVLINK_MSG_ID_LOG_REQUEST_END_LEN; - memset(log_request_end, 0, MAVLINK_MSG_ID_LOG_REQUEST_END_LEN); - memcpy(log_request_end, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_log_request_list.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_log_request_list.h deleted file mode 100644 index de193356..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_log_request_list.h +++ /dev/null @@ -1,288 +0,0 @@ -#pragma once -// MESSAGE LOG_REQUEST_LIST PACKING - -#define MAVLINK_MSG_ID_LOG_REQUEST_LIST 117 - - -typedef struct __mavlink_log_request_list_t { - uint16_t start; /*< First log id (0 for first available)*/ - uint16_t end; /*< Last log id (0xffff for last available)*/ - uint8_t target_system; /*< System ID*/ - uint8_t target_component; /*< Component ID*/ -} mavlink_log_request_list_t; - -#define MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN 6 -#define MAVLINK_MSG_ID_LOG_REQUEST_LIST_MIN_LEN 6 -#define MAVLINK_MSG_ID_117_LEN 6 -#define MAVLINK_MSG_ID_117_MIN_LEN 6 - -#define MAVLINK_MSG_ID_LOG_REQUEST_LIST_CRC 128 -#define MAVLINK_MSG_ID_117_CRC 128 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_LOG_REQUEST_LIST { \ - 117, \ - "LOG_REQUEST_LIST", \ - 4, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_log_request_list_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_log_request_list_t, target_component) }, \ - { "start", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_log_request_list_t, start) }, \ - { "end", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_log_request_list_t, end) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_LOG_REQUEST_LIST { \ - "LOG_REQUEST_LIST", \ - 4, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_log_request_list_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_log_request_list_t, target_component) }, \ - { "start", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_log_request_list_t, start) }, \ - { "end", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_log_request_list_t, end) }, \ - } \ -} -#endif - -/** - * @brief Pack a log_request_list message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID - * @param target_component Component ID - * @param start First log id (0 for first available) - * @param end Last log id (0xffff for last available) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_log_request_list_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component, uint16_t start, uint16_t end) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN]; - _mav_put_uint16_t(buf, 0, start); - _mav_put_uint16_t(buf, 2, end); - _mav_put_uint8_t(buf, 4, target_system); - _mav_put_uint8_t(buf, 5, target_component); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN); -#else - mavlink_log_request_list_t packet; - packet.start = start; - packet.end = end; - packet.target_system = target_system; - packet.target_component = target_component; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_LOG_REQUEST_LIST; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOG_REQUEST_LIST_MIN_LEN, MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN, MAVLINK_MSG_ID_LOG_REQUEST_LIST_CRC); -} - -/** - * @brief Pack a log_request_list message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @param start First log id (0 for first available) - * @param end Last log id (0xffff for last available) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_log_request_list_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component,uint16_t start,uint16_t end) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN]; - _mav_put_uint16_t(buf, 0, start); - _mav_put_uint16_t(buf, 2, end); - _mav_put_uint8_t(buf, 4, target_system); - _mav_put_uint8_t(buf, 5, target_component); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN); -#else - mavlink_log_request_list_t packet; - packet.start = start; - packet.end = end; - packet.target_system = target_system; - packet.target_component = target_component; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_LOG_REQUEST_LIST; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOG_REQUEST_LIST_MIN_LEN, MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN, MAVLINK_MSG_ID_LOG_REQUEST_LIST_CRC); -} - -/** - * @brief Encode a log_request_list struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param log_request_list C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_log_request_list_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_log_request_list_t* log_request_list) -{ - return mavlink_msg_log_request_list_pack(system_id, component_id, msg, log_request_list->target_system, log_request_list->target_component, log_request_list->start, log_request_list->end); -} - -/** - * @brief Encode a log_request_list struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param log_request_list C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_log_request_list_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_log_request_list_t* log_request_list) -{ - return mavlink_msg_log_request_list_pack_chan(system_id, component_id, chan, msg, log_request_list->target_system, log_request_list->target_component, log_request_list->start, log_request_list->end); -} - -/** - * @brief Send a log_request_list message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param target_component Component ID - * @param start First log id (0 for first available) - * @param end Last log id (0xffff for last available) - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_log_request_list_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t start, uint16_t end) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN]; - _mav_put_uint16_t(buf, 0, start); - _mav_put_uint16_t(buf, 2, end); - _mav_put_uint8_t(buf, 4, target_system); - _mav_put_uint8_t(buf, 5, target_component); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_LIST, buf, MAVLINK_MSG_ID_LOG_REQUEST_LIST_MIN_LEN, MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN, MAVLINK_MSG_ID_LOG_REQUEST_LIST_CRC); -#else - mavlink_log_request_list_t packet; - packet.start = start; - packet.end = end; - packet.target_system = target_system; - packet.target_component = target_component; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_LIST, (const char *)&packet, MAVLINK_MSG_ID_LOG_REQUEST_LIST_MIN_LEN, MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN, MAVLINK_MSG_ID_LOG_REQUEST_LIST_CRC); -#endif -} - -/** - * @brief Send a log_request_list message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_log_request_list_send_struct(mavlink_channel_t chan, const mavlink_log_request_list_t* log_request_list) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_log_request_list_send(chan, log_request_list->target_system, log_request_list->target_component, log_request_list->start, log_request_list->end); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_LIST, (const char *)log_request_list, MAVLINK_MSG_ID_LOG_REQUEST_LIST_MIN_LEN, MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN, MAVLINK_MSG_ID_LOG_REQUEST_LIST_CRC); -#endif -} - -#if MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_log_request_list_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t start, uint16_t end) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint16_t(buf, 0, start); - _mav_put_uint16_t(buf, 2, end); - _mav_put_uint8_t(buf, 4, target_system); - _mav_put_uint8_t(buf, 5, target_component); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_LIST, buf, MAVLINK_MSG_ID_LOG_REQUEST_LIST_MIN_LEN, MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN, MAVLINK_MSG_ID_LOG_REQUEST_LIST_CRC); -#else - mavlink_log_request_list_t *packet = (mavlink_log_request_list_t *)msgbuf; - packet->start = start; - packet->end = end; - packet->target_system = target_system; - packet->target_component = target_component; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_LIST, (const char *)packet, MAVLINK_MSG_ID_LOG_REQUEST_LIST_MIN_LEN, MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN, MAVLINK_MSG_ID_LOG_REQUEST_LIST_CRC); -#endif -} -#endif - -#endif - -// MESSAGE LOG_REQUEST_LIST UNPACKING - - -/** - * @brief Get field target_system from log_request_list message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_log_request_list_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 4); -} - -/** - * @brief Get field target_component from log_request_list message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_log_request_list_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 5); -} - -/** - * @brief Get field start from log_request_list message - * - * @return First log id (0 for first available) - */ -static inline uint16_t mavlink_msg_log_request_list_get_start(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 0); -} - -/** - * @brief Get field end from log_request_list message - * - * @return Last log id (0xffff for last available) - */ -static inline uint16_t mavlink_msg_log_request_list_get_end(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 2); -} - -/** - * @brief Decode a log_request_list message into a struct - * - * @param msg The message to decode - * @param log_request_list C-struct to decode the message contents into - */ -static inline void mavlink_msg_log_request_list_decode(const mavlink_message_t* msg, mavlink_log_request_list_t* log_request_list) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - log_request_list->start = mavlink_msg_log_request_list_get_start(msg); - log_request_list->end = mavlink_msg_log_request_list_get_end(msg); - log_request_list->target_system = mavlink_msg_log_request_list_get_target_system(msg); - log_request_list->target_component = mavlink_msg_log_request_list_get_target_component(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN? msg->len : MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN; - memset(log_request_list, 0, MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN); - memcpy(log_request_list, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_logging_ack.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_logging_ack.h deleted file mode 100644 index 66471061..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_logging_ack.h +++ /dev/null @@ -1,263 +0,0 @@ -#pragma once -// MESSAGE LOGGING_ACK PACKING - -#define MAVLINK_MSG_ID_LOGGING_ACK 268 - - -typedef struct __mavlink_logging_ack_t { - uint16_t sequence; /*< sequence number (must match the one in LOGGING_DATA_ACKED)*/ - uint8_t target_system; /*< system ID of the target*/ - uint8_t target_component; /*< component ID of the target*/ -} mavlink_logging_ack_t; - -#define MAVLINK_MSG_ID_LOGGING_ACK_LEN 4 -#define MAVLINK_MSG_ID_LOGGING_ACK_MIN_LEN 4 -#define MAVLINK_MSG_ID_268_LEN 4 -#define MAVLINK_MSG_ID_268_MIN_LEN 4 - -#define MAVLINK_MSG_ID_LOGGING_ACK_CRC 14 -#define MAVLINK_MSG_ID_268_CRC 14 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_LOGGING_ACK { \ - 268, \ - "LOGGING_ACK", \ - 3, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_logging_ack_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_logging_ack_t, target_component) }, \ - { "sequence", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_logging_ack_t, sequence) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_LOGGING_ACK { \ - "LOGGING_ACK", \ - 3, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_logging_ack_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_logging_ack_t, target_component) }, \ - { "sequence", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_logging_ack_t, sequence) }, \ - } \ -} -#endif - -/** - * @brief Pack a logging_ack message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system system ID of the target - * @param target_component component ID of the target - * @param sequence sequence number (must match the one in LOGGING_DATA_ACKED) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_logging_ack_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component, uint16_t sequence) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LOGGING_ACK_LEN]; - _mav_put_uint16_t(buf, 0, sequence); - _mav_put_uint8_t(buf, 2, target_system); - _mav_put_uint8_t(buf, 3, target_component); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOGGING_ACK_LEN); -#else - mavlink_logging_ack_t packet; - packet.sequence = sequence; - packet.target_system = target_system; - packet.target_component = target_component; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOGGING_ACK_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_LOGGING_ACK; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOGGING_ACK_MIN_LEN, MAVLINK_MSG_ID_LOGGING_ACK_LEN, MAVLINK_MSG_ID_LOGGING_ACK_CRC); -} - -/** - * @brief Pack a logging_ack message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system system ID of the target - * @param target_component component ID of the target - * @param sequence sequence number (must match the one in LOGGING_DATA_ACKED) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_logging_ack_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component,uint16_t sequence) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LOGGING_ACK_LEN]; - _mav_put_uint16_t(buf, 0, sequence); - _mav_put_uint8_t(buf, 2, target_system); - _mav_put_uint8_t(buf, 3, target_component); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOGGING_ACK_LEN); -#else - mavlink_logging_ack_t packet; - packet.sequence = sequence; - packet.target_system = target_system; - packet.target_component = target_component; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOGGING_ACK_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_LOGGING_ACK; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOGGING_ACK_MIN_LEN, MAVLINK_MSG_ID_LOGGING_ACK_LEN, MAVLINK_MSG_ID_LOGGING_ACK_CRC); -} - -/** - * @brief Encode a logging_ack struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param logging_ack C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_logging_ack_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_logging_ack_t* logging_ack) -{ - return mavlink_msg_logging_ack_pack(system_id, component_id, msg, logging_ack->target_system, logging_ack->target_component, logging_ack->sequence); -} - -/** - * @brief Encode a logging_ack struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param logging_ack C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_logging_ack_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_logging_ack_t* logging_ack) -{ - return mavlink_msg_logging_ack_pack_chan(system_id, component_id, chan, msg, logging_ack->target_system, logging_ack->target_component, logging_ack->sequence); -} - -/** - * @brief Send a logging_ack message - * @param chan MAVLink channel to send the message - * - * @param target_system system ID of the target - * @param target_component component ID of the target - * @param sequence sequence number (must match the one in LOGGING_DATA_ACKED) - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_logging_ack_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t sequence) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LOGGING_ACK_LEN]; - _mav_put_uint16_t(buf, 0, sequence); - _mav_put_uint8_t(buf, 2, target_system); - _mav_put_uint8_t(buf, 3, target_component); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOGGING_ACK, buf, MAVLINK_MSG_ID_LOGGING_ACK_MIN_LEN, MAVLINK_MSG_ID_LOGGING_ACK_LEN, MAVLINK_MSG_ID_LOGGING_ACK_CRC); -#else - mavlink_logging_ack_t packet; - packet.sequence = sequence; - packet.target_system = target_system; - packet.target_component = target_component; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOGGING_ACK, (const char *)&packet, MAVLINK_MSG_ID_LOGGING_ACK_MIN_LEN, MAVLINK_MSG_ID_LOGGING_ACK_LEN, MAVLINK_MSG_ID_LOGGING_ACK_CRC); -#endif -} - -/** - * @brief Send a logging_ack message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_logging_ack_send_struct(mavlink_channel_t chan, const mavlink_logging_ack_t* logging_ack) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_logging_ack_send(chan, logging_ack->target_system, logging_ack->target_component, logging_ack->sequence); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOGGING_ACK, (const char *)logging_ack, MAVLINK_MSG_ID_LOGGING_ACK_MIN_LEN, MAVLINK_MSG_ID_LOGGING_ACK_LEN, MAVLINK_MSG_ID_LOGGING_ACK_CRC); -#endif -} - -#if MAVLINK_MSG_ID_LOGGING_ACK_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_logging_ack_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t sequence) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint16_t(buf, 0, sequence); - _mav_put_uint8_t(buf, 2, target_system); - _mav_put_uint8_t(buf, 3, target_component); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOGGING_ACK, buf, MAVLINK_MSG_ID_LOGGING_ACK_MIN_LEN, MAVLINK_MSG_ID_LOGGING_ACK_LEN, MAVLINK_MSG_ID_LOGGING_ACK_CRC); -#else - mavlink_logging_ack_t *packet = (mavlink_logging_ack_t *)msgbuf; - packet->sequence = sequence; - packet->target_system = target_system; - packet->target_component = target_component; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOGGING_ACK, (const char *)packet, MAVLINK_MSG_ID_LOGGING_ACK_MIN_LEN, MAVLINK_MSG_ID_LOGGING_ACK_LEN, MAVLINK_MSG_ID_LOGGING_ACK_CRC); -#endif -} -#endif - -#endif - -// MESSAGE LOGGING_ACK UNPACKING - - -/** - * @brief Get field target_system from logging_ack message - * - * @return system ID of the target - */ -static inline uint8_t mavlink_msg_logging_ack_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 2); -} - -/** - * @brief Get field target_component from logging_ack message - * - * @return component ID of the target - */ -static inline uint8_t mavlink_msg_logging_ack_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 3); -} - -/** - * @brief Get field sequence from logging_ack message - * - * @return sequence number (must match the one in LOGGING_DATA_ACKED) - */ -static inline uint16_t mavlink_msg_logging_ack_get_sequence(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 0); -} - -/** - * @brief Decode a logging_ack message into a struct - * - * @param msg The message to decode - * @param logging_ack C-struct to decode the message contents into - */ -static inline void mavlink_msg_logging_ack_decode(const mavlink_message_t* msg, mavlink_logging_ack_t* logging_ack) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - logging_ack->sequence = mavlink_msg_logging_ack_get_sequence(msg); - logging_ack->target_system = mavlink_msg_logging_ack_get_target_system(msg); - logging_ack->target_component = mavlink_msg_logging_ack_get_target_component(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_LOGGING_ACK_LEN? msg->len : MAVLINK_MSG_ID_LOGGING_ACK_LEN; - memset(logging_ack, 0, MAVLINK_MSG_ID_LOGGING_ACK_LEN); - memcpy(logging_ack, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_logging_data.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_logging_data.h deleted file mode 100644 index fa2fa235..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_logging_data.h +++ /dev/null @@ -1,330 +0,0 @@ -#pragma once -// MESSAGE LOGGING_DATA PACKING - -#define MAVLINK_MSG_ID_LOGGING_DATA 266 - - -typedef struct __mavlink_logging_data_t { - uint16_t sequence; /*< sequence number (can wrap)*/ - uint8_t target_system; /*< system ID of the target*/ - uint8_t target_component; /*< component ID of the target*/ - uint8_t length; /*< [bytes] data length*/ - uint8_t first_message_offset; /*< [bytes] offset into data where first message starts. This can be used for recovery, when a previous message got lost (set to UINT8_MAX if no start exists).*/ - uint8_t data[249]; /*< logged data*/ -} mavlink_logging_data_t; - -#define MAVLINK_MSG_ID_LOGGING_DATA_LEN 255 -#define MAVLINK_MSG_ID_LOGGING_DATA_MIN_LEN 255 -#define MAVLINK_MSG_ID_266_LEN 255 -#define MAVLINK_MSG_ID_266_MIN_LEN 255 - -#define MAVLINK_MSG_ID_LOGGING_DATA_CRC 193 -#define MAVLINK_MSG_ID_266_CRC 193 - -#define MAVLINK_MSG_LOGGING_DATA_FIELD_DATA_LEN 249 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_LOGGING_DATA { \ - 266, \ - "LOGGING_DATA", \ - 6, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_logging_data_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_logging_data_t, target_component) }, \ - { "sequence", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_logging_data_t, sequence) }, \ - { "length", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_logging_data_t, length) }, \ - { "first_message_offset", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_logging_data_t, first_message_offset) }, \ - { "data", NULL, MAVLINK_TYPE_UINT8_T, 249, 6, offsetof(mavlink_logging_data_t, data) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_LOGGING_DATA { \ - "LOGGING_DATA", \ - 6, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_logging_data_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_logging_data_t, target_component) }, \ - { "sequence", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_logging_data_t, sequence) }, \ - { "length", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_logging_data_t, length) }, \ - { "first_message_offset", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_logging_data_t, first_message_offset) }, \ - { "data", NULL, MAVLINK_TYPE_UINT8_T, 249, 6, offsetof(mavlink_logging_data_t, data) }, \ - } \ -} -#endif - -/** - * @brief Pack a logging_data message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system system ID of the target - * @param target_component component ID of the target - * @param sequence sequence number (can wrap) - * @param length [bytes] data length - * @param first_message_offset [bytes] offset into data where first message starts. This can be used for recovery, when a previous message got lost (set to UINT8_MAX if no start exists). - * @param data logged data - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_logging_data_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component, uint16_t sequence, uint8_t length, uint8_t first_message_offset, const uint8_t *data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LOGGING_DATA_LEN]; - _mav_put_uint16_t(buf, 0, sequence); - _mav_put_uint8_t(buf, 2, target_system); - _mav_put_uint8_t(buf, 3, target_component); - _mav_put_uint8_t(buf, 4, length); - _mav_put_uint8_t(buf, 5, first_message_offset); - _mav_put_uint8_t_array(buf, 6, data, 249); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOGGING_DATA_LEN); -#else - mavlink_logging_data_t packet; - packet.sequence = sequence; - packet.target_system = target_system; - packet.target_component = target_component; - packet.length = length; - packet.first_message_offset = first_message_offset; - mav_array_memcpy(packet.data, data, sizeof(uint8_t)*249); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOGGING_DATA_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_LOGGING_DATA; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOGGING_DATA_MIN_LEN, MAVLINK_MSG_ID_LOGGING_DATA_LEN, MAVLINK_MSG_ID_LOGGING_DATA_CRC); -} - -/** - * @brief Pack a logging_data message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system system ID of the target - * @param target_component component ID of the target - * @param sequence sequence number (can wrap) - * @param length [bytes] data length - * @param first_message_offset [bytes] offset into data where first message starts. This can be used for recovery, when a previous message got lost (set to UINT8_MAX if no start exists). - * @param data logged data - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_logging_data_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component,uint16_t sequence,uint8_t length,uint8_t first_message_offset,const uint8_t *data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LOGGING_DATA_LEN]; - _mav_put_uint16_t(buf, 0, sequence); - _mav_put_uint8_t(buf, 2, target_system); - _mav_put_uint8_t(buf, 3, target_component); - _mav_put_uint8_t(buf, 4, length); - _mav_put_uint8_t(buf, 5, first_message_offset); - _mav_put_uint8_t_array(buf, 6, data, 249); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOGGING_DATA_LEN); -#else - mavlink_logging_data_t packet; - packet.sequence = sequence; - packet.target_system = target_system; - packet.target_component = target_component; - packet.length = length; - packet.first_message_offset = first_message_offset; - mav_array_memcpy(packet.data, data, sizeof(uint8_t)*249); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOGGING_DATA_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_LOGGING_DATA; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOGGING_DATA_MIN_LEN, MAVLINK_MSG_ID_LOGGING_DATA_LEN, MAVLINK_MSG_ID_LOGGING_DATA_CRC); -} - -/** - * @brief Encode a logging_data struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param logging_data C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_logging_data_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_logging_data_t* logging_data) -{ - return mavlink_msg_logging_data_pack(system_id, component_id, msg, logging_data->target_system, logging_data->target_component, logging_data->sequence, logging_data->length, logging_data->first_message_offset, logging_data->data); -} - -/** - * @brief Encode a logging_data struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param logging_data C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_logging_data_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_logging_data_t* logging_data) -{ - return mavlink_msg_logging_data_pack_chan(system_id, component_id, chan, msg, logging_data->target_system, logging_data->target_component, logging_data->sequence, logging_data->length, logging_data->first_message_offset, logging_data->data); -} - -/** - * @brief Send a logging_data message - * @param chan MAVLink channel to send the message - * - * @param target_system system ID of the target - * @param target_component component ID of the target - * @param sequence sequence number (can wrap) - * @param length [bytes] data length - * @param first_message_offset [bytes] offset into data where first message starts. This can be used for recovery, when a previous message got lost (set to UINT8_MAX if no start exists). - * @param data logged data - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_logging_data_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t sequence, uint8_t length, uint8_t first_message_offset, const uint8_t *data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LOGGING_DATA_LEN]; - _mav_put_uint16_t(buf, 0, sequence); - _mav_put_uint8_t(buf, 2, target_system); - _mav_put_uint8_t(buf, 3, target_component); - _mav_put_uint8_t(buf, 4, length); - _mav_put_uint8_t(buf, 5, first_message_offset); - _mav_put_uint8_t_array(buf, 6, data, 249); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOGGING_DATA, buf, MAVLINK_MSG_ID_LOGGING_DATA_MIN_LEN, MAVLINK_MSG_ID_LOGGING_DATA_LEN, MAVLINK_MSG_ID_LOGGING_DATA_CRC); -#else - mavlink_logging_data_t packet; - packet.sequence = sequence; - packet.target_system = target_system; - packet.target_component = target_component; - packet.length = length; - packet.first_message_offset = first_message_offset; - mav_array_memcpy(packet.data, data, sizeof(uint8_t)*249); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOGGING_DATA, (const char *)&packet, MAVLINK_MSG_ID_LOGGING_DATA_MIN_LEN, MAVLINK_MSG_ID_LOGGING_DATA_LEN, MAVLINK_MSG_ID_LOGGING_DATA_CRC); -#endif -} - -/** - * @brief Send a logging_data message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_logging_data_send_struct(mavlink_channel_t chan, const mavlink_logging_data_t* logging_data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_logging_data_send(chan, logging_data->target_system, logging_data->target_component, logging_data->sequence, logging_data->length, logging_data->first_message_offset, logging_data->data); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOGGING_DATA, (const char *)logging_data, MAVLINK_MSG_ID_LOGGING_DATA_MIN_LEN, MAVLINK_MSG_ID_LOGGING_DATA_LEN, MAVLINK_MSG_ID_LOGGING_DATA_CRC); -#endif -} - -#if MAVLINK_MSG_ID_LOGGING_DATA_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_logging_data_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t sequence, uint8_t length, uint8_t first_message_offset, const uint8_t *data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint16_t(buf, 0, sequence); - _mav_put_uint8_t(buf, 2, target_system); - _mav_put_uint8_t(buf, 3, target_component); - _mav_put_uint8_t(buf, 4, length); - _mav_put_uint8_t(buf, 5, first_message_offset); - _mav_put_uint8_t_array(buf, 6, data, 249); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOGGING_DATA, buf, MAVLINK_MSG_ID_LOGGING_DATA_MIN_LEN, MAVLINK_MSG_ID_LOGGING_DATA_LEN, MAVLINK_MSG_ID_LOGGING_DATA_CRC); -#else - mavlink_logging_data_t *packet = (mavlink_logging_data_t *)msgbuf; - packet->sequence = sequence; - packet->target_system = target_system; - packet->target_component = target_component; - packet->length = length; - packet->first_message_offset = first_message_offset; - mav_array_memcpy(packet->data, data, sizeof(uint8_t)*249); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOGGING_DATA, (const char *)packet, MAVLINK_MSG_ID_LOGGING_DATA_MIN_LEN, MAVLINK_MSG_ID_LOGGING_DATA_LEN, MAVLINK_MSG_ID_LOGGING_DATA_CRC); -#endif -} -#endif - -#endif - -// MESSAGE LOGGING_DATA UNPACKING - - -/** - * @brief Get field target_system from logging_data message - * - * @return system ID of the target - */ -static inline uint8_t mavlink_msg_logging_data_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 2); -} - -/** - * @brief Get field target_component from logging_data message - * - * @return component ID of the target - */ -static inline uint8_t mavlink_msg_logging_data_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 3); -} - -/** - * @brief Get field sequence from logging_data message - * - * @return sequence number (can wrap) - */ -static inline uint16_t mavlink_msg_logging_data_get_sequence(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 0); -} - -/** - * @brief Get field length from logging_data message - * - * @return [bytes] data length - */ -static inline uint8_t mavlink_msg_logging_data_get_length(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 4); -} - -/** - * @brief Get field first_message_offset from logging_data message - * - * @return [bytes] offset into data where first message starts. This can be used for recovery, when a previous message got lost (set to UINT8_MAX if no start exists). - */ -static inline uint8_t mavlink_msg_logging_data_get_first_message_offset(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 5); -} - -/** - * @brief Get field data from logging_data message - * - * @return logged data - */ -static inline uint16_t mavlink_msg_logging_data_get_data(const mavlink_message_t* msg, uint8_t *data) -{ - return _MAV_RETURN_uint8_t_array(msg, data, 249, 6); -} - -/** - * @brief Decode a logging_data message into a struct - * - * @param msg The message to decode - * @param logging_data C-struct to decode the message contents into - */ -static inline void mavlink_msg_logging_data_decode(const mavlink_message_t* msg, mavlink_logging_data_t* logging_data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - logging_data->sequence = mavlink_msg_logging_data_get_sequence(msg); - logging_data->target_system = mavlink_msg_logging_data_get_target_system(msg); - logging_data->target_component = mavlink_msg_logging_data_get_target_component(msg); - logging_data->length = mavlink_msg_logging_data_get_length(msg); - logging_data->first_message_offset = mavlink_msg_logging_data_get_first_message_offset(msg); - mavlink_msg_logging_data_get_data(msg, logging_data->data); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_LOGGING_DATA_LEN? msg->len : MAVLINK_MSG_ID_LOGGING_DATA_LEN; - memset(logging_data, 0, MAVLINK_MSG_ID_LOGGING_DATA_LEN); - memcpy(logging_data, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_logging_data_acked.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_logging_data_acked.h deleted file mode 100644 index 15618d5b..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_logging_data_acked.h +++ /dev/null @@ -1,330 +0,0 @@ -#pragma once -// MESSAGE LOGGING_DATA_ACKED PACKING - -#define MAVLINK_MSG_ID_LOGGING_DATA_ACKED 267 - - -typedef struct __mavlink_logging_data_acked_t { - uint16_t sequence; /*< sequence number (can wrap)*/ - uint8_t target_system; /*< system ID of the target*/ - uint8_t target_component; /*< component ID of the target*/ - uint8_t length; /*< [bytes] data length*/ - uint8_t first_message_offset; /*< [bytes] offset into data where first message starts. This can be used for recovery, when a previous message got lost (set to UINT8_MAX if no start exists).*/ - uint8_t data[249]; /*< logged data*/ -} mavlink_logging_data_acked_t; - -#define MAVLINK_MSG_ID_LOGGING_DATA_ACKED_LEN 255 -#define MAVLINK_MSG_ID_LOGGING_DATA_ACKED_MIN_LEN 255 -#define MAVLINK_MSG_ID_267_LEN 255 -#define MAVLINK_MSG_ID_267_MIN_LEN 255 - -#define MAVLINK_MSG_ID_LOGGING_DATA_ACKED_CRC 35 -#define MAVLINK_MSG_ID_267_CRC 35 - -#define MAVLINK_MSG_LOGGING_DATA_ACKED_FIELD_DATA_LEN 249 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_LOGGING_DATA_ACKED { \ - 267, \ - "LOGGING_DATA_ACKED", \ - 6, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_logging_data_acked_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_logging_data_acked_t, target_component) }, \ - { "sequence", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_logging_data_acked_t, sequence) }, \ - { "length", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_logging_data_acked_t, length) }, \ - { "first_message_offset", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_logging_data_acked_t, first_message_offset) }, \ - { "data", NULL, MAVLINK_TYPE_UINT8_T, 249, 6, offsetof(mavlink_logging_data_acked_t, data) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_LOGGING_DATA_ACKED { \ - "LOGGING_DATA_ACKED", \ - 6, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_logging_data_acked_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_logging_data_acked_t, target_component) }, \ - { "sequence", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_logging_data_acked_t, sequence) }, \ - { "length", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_logging_data_acked_t, length) }, \ - { "first_message_offset", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_logging_data_acked_t, first_message_offset) }, \ - { "data", NULL, MAVLINK_TYPE_UINT8_T, 249, 6, offsetof(mavlink_logging_data_acked_t, data) }, \ - } \ -} -#endif - -/** - * @brief Pack a logging_data_acked message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system system ID of the target - * @param target_component component ID of the target - * @param sequence sequence number (can wrap) - * @param length [bytes] data length - * @param first_message_offset [bytes] offset into data where first message starts. This can be used for recovery, when a previous message got lost (set to UINT8_MAX if no start exists). - * @param data logged data - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_logging_data_acked_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component, uint16_t sequence, uint8_t length, uint8_t first_message_offset, const uint8_t *data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LOGGING_DATA_ACKED_LEN]; - _mav_put_uint16_t(buf, 0, sequence); - _mav_put_uint8_t(buf, 2, target_system); - _mav_put_uint8_t(buf, 3, target_component); - _mav_put_uint8_t(buf, 4, length); - _mav_put_uint8_t(buf, 5, first_message_offset); - _mav_put_uint8_t_array(buf, 6, data, 249); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOGGING_DATA_ACKED_LEN); -#else - mavlink_logging_data_acked_t packet; - packet.sequence = sequence; - packet.target_system = target_system; - packet.target_component = target_component; - packet.length = length; - packet.first_message_offset = first_message_offset; - mav_array_memcpy(packet.data, data, sizeof(uint8_t)*249); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOGGING_DATA_ACKED_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_LOGGING_DATA_ACKED; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOGGING_DATA_ACKED_MIN_LEN, MAVLINK_MSG_ID_LOGGING_DATA_ACKED_LEN, MAVLINK_MSG_ID_LOGGING_DATA_ACKED_CRC); -} - -/** - * @brief Pack a logging_data_acked message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system system ID of the target - * @param target_component component ID of the target - * @param sequence sequence number (can wrap) - * @param length [bytes] data length - * @param first_message_offset [bytes] offset into data where first message starts. This can be used for recovery, when a previous message got lost (set to UINT8_MAX if no start exists). - * @param data logged data - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_logging_data_acked_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component,uint16_t sequence,uint8_t length,uint8_t first_message_offset,const uint8_t *data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LOGGING_DATA_ACKED_LEN]; - _mav_put_uint16_t(buf, 0, sequence); - _mav_put_uint8_t(buf, 2, target_system); - _mav_put_uint8_t(buf, 3, target_component); - _mav_put_uint8_t(buf, 4, length); - _mav_put_uint8_t(buf, 5, first_message_offset); - _mav_put_uint8_t_array(buf, 6, data, 249); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOGGING_DATA_ACKED_LEN); -#else - mavlink_logging_data_acked_t packet; - packet.sequence = sequence; - packet.target_system = target_system; - packet.target_component = target_component; - packet.length = length; - packet.first_message_offset = first_message_offset; - mav_array_memcpy(packet.data, data, sizeof(uint8_t)*249); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOGGING_DATA_ACKED_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_LOGGING_DATA_ACKED; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOGGING_DATA_ACKED_MIN_LEN, MAVLINK_MSG_ID_LOGGING_DATA_ACKED_LEN, MAVLINK_MSG_ID_LOGGING_DATA_ACKED_CRC); -} - -/** - * @brief Encode a logging_data_acked struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param logging_data_acked C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_logging_data_acked_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_logging_data_acked_t* logging_data_acked) -{ - return mavlink_msg_logging_data_acked_pack(system_id, component_id, msg, logging_data_acked->target_system, logging_data_acked->target_component, logging_data_acked->sequence, logging_data_acked->length, logging_data_acked->first_message_offset, logging_data_acked->data); -} - -/** - * @brief Encode a logging_data_acked struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param logging_data_acked C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_logging_data_acked_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_logging_data_acked_t* logging_data_acked) -{ - return mavlink_msg_logging_data_acked_pack_chan(system_id, component_id, chan, msg, logging_data_acked->target_system, logging_data_acked->target_component, logging_data_acked->sequence, logging_data_acked->length, logging_data_acked->first_message_offset, logging_data_acked->data); -} - -/** - * @brief Send a logging_data_acked message - * @param chan MAVLink channel to send the message - * - * @param target_system system ID of the target - * @param target_component component ID of the target - * @param sequence sequence number (can wrap) - * @param length [bytes] data length - * @param first_message_offset [bytes] offset into data where first message starts. This can be used for recovery, when a previous message got lost (set to UINT8_MAX if no start exists). - * @param data logged data - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_logging_data_acked_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t sequence, uint8_t length, uint8_t first_message_offset, const uint8_t *data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LOGGING_DATA_ACKED_LEN]; - _mav_put_uint16_t(buf, 0, sequence); - _mav_put_uint8_t(buf, 2, target_system); - _mav_put_uint8_t(buf, 3, target_component); - _mav_put_uint8_t(buf, 4, length); - _mav_put_uint8_t(buf, 5, first_message_offset); - _mav_put_uint8_t_array(buf, 6, data, 249); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOGGING_DATA_ACKED, buf, MAVLINK_MSG_ID_LOGGING_DATA_ACKED_MIN_LEN, MAVLINK_MSG_ID_LOGGING_DATA_ACKED_LEN, MAVLINK_MSG_ID_LOGGING_DATA_ACKED_CRC); -#else - mavlink_logging_data_acked_t packet; - packet.sequence = sequence; - packet.target_system = target_system; - packet.target_component = target_component; - packet.length = length; - packet.first_message_offset = first_message_offset; - mav_array_memcpy(packet.data, data, sizeof(uint8_t)*249); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOGGING_DATA_ACKED, (const char *)&packet, MAVLINK_MSG_ID_LOGGING_DATA_ACKED_MIN_LEN, MAVLINK_MSG_ID_LOGGING_DATA_ACKED_LEN, MAVLINK_MSG_ID_LOGGING_DATA_ACKED_CRC); -#endif -} - -/** - * @brief Send a logging_data_acked message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_logging_data_acked_send_struct(mavlink_channel_t chan, const mavlink_logging_data_acked_t* logging_data_acked) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_logging_data_acked_send(chan, logging_data_acked->target_system, logging_data_acked->target_component, logging_data_acked->sequence, logging_data_acked->length, logging_data_acked->first_message_offset, logging_data_acked->data); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOGGING_DATA_ACKED, (const char *)logging_data_acked, MAVLINK_MSG_ID_LOGGING_DATA_ACKED_MIN_LEN, MAVLINK_MSG_ID_LOGGING_DATA_ACKED_LEN, MAVLINK_MSG_ID_LOGGING_DATA_ACKED_CRC); -#endif -} - -#if MAVLINK_MSG_ID_LOGGING_DATA_ACKED_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_logging_data_acked_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t sequence, uint8_t length, uint8_t first_message_offset, const uint8_t *data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint16_t(buf, 0, sequence); - _mav_put_uint8_t(buf, 2, target_system); - _mav_put_uint8_t(buf, 3, target_component); - _mav_put_uint8_t(buf, 4, length); - _mav_put_uint8_t(buf, 5, first_message_offset); - _mav_put_uint8_t_array(buf, 6, data, 249); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOGGING_DATA_ACKED, buf, MAVLINK_MSG_ID_LOGGING_DATA_ACKED_MIN_LEN, MAVLINK_MSG_ID_LOGGING_DATA_ACKED_LEN, MAVLINK_MSG_ID_LOGGING_DATA_ACKED_CRC); -#else - mavlink_logging_data_acked_t *packet = (mavlink_logging_data_acked_t *)msgbuf; - packet->sequence = sequence; - packet->target_system = target_system; - packet->target_component = target_component; - packet->length = length; - packet->first_message_offset = first_message_offset; - mav_array_memcpy(packet->data, data, sizeof(uint8_t)*249); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOGGING_DATA_ACKED, (const char *)packet, MAVLINK_MSG_ID_LOGGING_DATA_ACKED_MIN_LEN, MAVLINK_MSG_ID_LOGGING_DATA_ACKED_LEN, MAVLINK_MSG_ID_LOGGING_DATA_ACKED_CRC); -#endif -} -#endif - -#endif - -// MESSAGE LOGGING_DATA_ACKED UNPACKING - - -/** - * @brief Get field target_system from logging_data_acked message - * - * @return system ID of the target - */ -static inline uint8_t mavlink_msg_logging_data_acked_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 2); -} - -/** - * @brief Get field target_component from logging_data_acked message - * - * @return component ID of the target - */ -static inline uint8_t mavlink_msg_logging_data_acked_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 3); -} - -/** - * @brief Get field sequence from logging_data_acked message - * - * @return sequence number (can wrap) - */ -static inline uint16_t mavlink_msg_logging_data_acked_get_sequence(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 0); -} - -/** - * @brief Get field length from logging_data_acked message - * - * @return [bytes] data length - */ -static inline uint8_t mavlink_msg_logging_data_acked_get_length(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 4); -} - -/** - * @brief Get field first_message_offset from logging_data_acked message - * - * @return [bytes] offset into data where first message starts. This can be used for recovery, when a previous message got lost (set to UINT8_MAX if no start exists). - */ -static inline uint8_t mavlink_msg_logging_data_acked_get_first_message_offset(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 5); -} - -/** - * @brief Get field data from logging_data_acked message - * - * @return logged data - */ -static inline uint16_t mavlink_msg_logging_data_acked_get_data(const mavlink_message_t* msg, uint8_t *data) -{ - return _MAV_RETURN_uint8_t_array(msg, data, 249, 6); -} - -/** - * @brief Decode a logging_data_acked message into a struct - * - * @param msg The message to decode - * @param logging_data_acked C-struct to decode the message contents into - */ -static inline void mavlink_msg_logging_data_acked_decode(const mavlink_message_t* msg, mavlink_logging_data_acked_t* logging_data_acked) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - logging_data_acked->sequence = mavlink_msg_logging_data_acked_get_sequence(msg); - logging_data_acked->target_system = mavlink_msg_logging_data_acked_get_target_system(msg); - logging_data_acked->target_component = mavlink_msg_logging_data_acked_get_target_component(msg); - logging_data_acked->length = mavlink_msg_logging_data_acked_get_length(msg); - logging_data_acked->first_message_offset = mavlink_msg_logging_data_acked_get_first_message_offset(msg); - mavlink_msg_logging_data_acked_get_data(msg, logging_data_acked->data); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_LOGGING_DATA_ACKED_LEN? msg->len : MAVLINK_MSG_ID_LOGGING_DATA_ACKED_LEN; - memset(logging_data_acked, 0, MAVLINK_MSG_ID_LOGGING_DATA_ACKED_LEN); - memcpy(logging_data_acked, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_mag_cal_report.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_mag_cal_report.h deleted file mode 100644 index 43e0a750..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_mag_cal_report.h +++ /dev/null @@ -1,638 +0,0 @@ -#pragma once -// MESSAGE MAG_CAL_REPORT PACKING - -#define MAVLINK_MSG_ID_MAG_CAL_REPORT 192 - -MAVPACKED( -typedef struct __mavlink_mag_cal_report_t { - float fitness; /*< [mgauss] RMS milligauss residuals.*/ - float ofs_x; /*< X offset.*/ - float ofs_y; /*< Y offset.*/ - float ofs_z; /*< Z offset.*/ - float diag_x; /*< X diagonal (matrix 11).*/ - float diag_y; /*< Y diagonal (matrix 22).*/ - float diag_z; /*< Z diagonal (matrix 33).*/ - float offdiag_x; /*< X off-diagonal (matrix 12 and 21).*/ - float offdiag_y; /*< Y off-diagonal (matrix 13 and 31).*/ - float offdiag_z; /*< Z off-diagonal (matrix 32 and 23).*/ - uint8_t compass_id; /*< Compass being calibrated.*/ - uint8_t cal_mask; /*< Bitmask of compasses being calibrated.*/ - uint8_t cal_status; /*< Calibration Status.*/ - uint8_t autosaved; /*< 0=requires a MAV_CMD_DO_ACCEPT_MAG_CAL, 1=saved to parameters.*/ - float orientation_confidence; /*< Confidence in orientation (higher is better).*/ - uint8_t old_orientation; /*< orientation before calibration.*/ - uint8_t new_orientation; /*< orientation after calibration.*/ - float scale_factor; /*< field radius correction factor*/ -}) mavlink_mag_cal_report_t; - -#define MAVLINK_MSG_ID_MAG_CAL_REPORT_LEN 54 -#define MAVLINK_MSG_ID_MAG_CAL_REPORT_MIN_LEN 44 -#define MAVLINK_MSG_ID_192_LEN 54 -#define MAVLINK_MSG_ID_192_MIN_LEN 44 - -#define MAVLINK_MSG_ID_MAG_CAL_REPORT_CRC 36 -#define MAVLINK_MSG_ID_192_CRC 36 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_MAG_CAL_REPORT { \ - 192, \ - "MAG_CAL_REPORT", \ - 18, \ - { { "compass_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 40, offsetof(mavlink_mag_cal_report_t, compass_id) }, \ - { "cal_mask", NULL, MAVLINK_TYPE_UINT8_T, 0, 41, offsetof(mavlink_mag_cal_report_t, cal_mask) }, \ - { "cal_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 42, offsetof(mavlink_mag_cal_report_t, cal_status) }, \ - { "autosaved", NULL, MAVLINK_TYPE_UINT8_T, 0, 43, offsetof(mavlink_mag_cal_report_t, autosaved) }, \ - { "fitness", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_mag_cal_report_t, fitness) }, \ - { "ofs_x", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_mag_cal_report_t, ofs_x) }, \ - { "ofs_y", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_mag_cal_report_t, ofs_y) }, \ - { "ofs_z", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_mag_cal_report_t, ofs_z) }, \ - { "diag_x", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_mag_cal_report_t, diag_x) }, \ - { "diag_y", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_mag_cal_report_t, diag_y) }, \ - { "diag_z", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_mag_cal_report_t, diag_z) }, \ - { "offdiag_x", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_mag_cal_report_t, offdiag_x) }, \ - { "offdiag_y", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_mag_cal_report_t, offdiag_y) }, \ - { "offdiag_z", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_mag_cal_report_t, offdiag_z) }, \ - { "orientation_confidence", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_mag_cal_report_t, orientation_confidence) }, \ - { "old_orientation", NULL, MAVLINK_TYPE_UINT8_T, 0, 48, offsetof(mavlink_mag_cal_report_t, old_orientation) }, \ - { "new_orientation", NULL, MAVLINK_TYPE_UINT8_T, 0, 49, offsetof(mavlink_mag_cal_report_t, new_orientation) }, \ - { "scale_factor", NULL, MAVLINK_TYPE_FLOAT, 0, 50, offsetof(mavlink_mag_cal_report_t, scale_factor) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_MAG_CAL_REPORT { \ - "MAG_CAL_REPORT", \ - 18, \ - { { "compass_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 40, offsetof(mavlink_mag_cal_report_t, compass_id) }, \ - { "cal_mask", NULL, MAVLINK_TYPE_UINT8_T, 0, 41, offsetof(mavlink_mag_cal_report_t, cal_mask) }, \ - { "cal_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 42, offsetof(mavlink_mag_cal_report_t, cal_status) }, \ - { "autosaved", NULL, MAVLINK_TYPE_UINT8_T, 0, 43, offsetof(mavlink_mag_cal_report_t, autosaved) }, \ - { "fitness", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_mag_cal_report_t, fitness) }, \ - { "ofs_x", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_mag_cal_report_t, ofs_x) }, \ - { "ofs_y", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_mag_cal_report_t, ofs_y) }, \ - { "ofs_z", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_mag_cal_report_t, ofs_z) }, \ - { "diag_x", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_mag_cal_report_t, diag_x) }, \ - { "diag_y", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_mag_cal_report_t, diag_y) }, \ - { "diag_z", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_mag_cal_report_t, diag_z) }, \ - { "offdiag_x", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_mag_cal_report_t, offdiag_x) }, \ - { "offdiag_y", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_mag_cal_report_t, offdiag_y) }, \ - { "offdiag_z", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_mag_cal_report_t, offdiag_z) }, \ - { "orientation_confidence", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_mag_cal_report_t, orientation_confidence) }, \ - { "old_orientation", NULL, MAVLINK_TYPE_UINT8_T, 0, 48, offsetof(mavlink_mag_cal_report_t, old_orientation) }, \ - { "new_orientation", NULL, MAVLINK_TYPE_UINT8_T, 0, 49, offsetof(mavlink_mag_cal_report_t, new_orientation) }, \ - { "scale_factor", NULL, MAVLINK_TYPE_FLOAT, 0, 50, offsetof(mavlink_mag_cal_report_t, scale_factor) }, \ - } \ -} -#endif - -/** - * @brief Pack a mag_cal_report message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param compass_id Compass being calibrated. - * @param cal_mask Bitmask of compasses being calibrated. - * @param cal_status Calibration Status. - * @param autosaved 0=requires a MAV_CMD_DO_ACCEPT_MAG_CAL, 1=saved to parameters. - * @param fitness [mgauss] RMS milligauss residuals. - * @param ofs_x X offset. - * @param ofs_y Y offset. - * @param ofs_z Z offset. - * @param diag_x X diagonal (matrix 11). - * @param diag_y Y diagonal (matrix 22). - * @param diag_z Z diagonal (matrix 33). - * @param offdiag_x X off-diagonal (matrix 12 and 21). - * @param offdiag_y Y off-diagonal (matrix 13 and 31). - * @param offdiag_z Z off-diagonal (matrix 32 and 23). - * @param orientation_confidence Confidence in orientation (higher is better). - * @param old_orientation orientation before calibration. - * @param new_orientation orientation after calibration. - * @param scale_factor field radius correction factor - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_mag_cal_report_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t compass_id, uint8_t cal_mask, uint8_t cal_status, uint8_t autosaved, float fitness, float ofs_x, float ofs_y, float ofs_z, float diag_x, float diag_y, float diag_z, float offdiag_x, float offdiag_y, float offdiag_z, float orientation_confidence, uint8_t old_orientation, uint8_t new_orientation, float scale_factor) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MAG_CAL_REPORT_LEN]; - _mav_put_float(buf, 0, fitness); - _mav_put_float(buf, 4, ofs_x); - _mav_put_float(buf, 8, ofs_y); - _mav_put_float(buf, 12, ofs_z); - _mav_put_float(buf, 16, diag_x); - _mav_put_float(buf, 20, diag_y); - _mav_put_float(buf, 24, diag_z); - _mav_put_float(buf, 28, offdiag_x); - _mav_put_float(buf, 32, offdiag_y); - _mav_put_float(buf, 36, offdiag_z); - _mav_put_uint8_t(buf, 40, compass_id); - _mav_put_uint8_t(buf, 41, cal_mask); - _mav_put_uint8_t(buf, 42, cal_status); - _mav_put_uint8_t(buf, 43, autosaved); - _mav_put_float(buf, 44, orientation_confidence); - _mav_put_uint8_t(buf, 48, old_orientation); - _mav_put_uint8_t(buf, 49, new_orientation); - _mav_put_float(buf, 50, scale_factor); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MAG_CAL_REPORT_LEN); -#else - mavlink_mag_cal_report_t packet; - packet.fitness = fitness; - packet.ofs_x = ofs_x; - packet.ofs_y = ofs_y; - packet.ofs_z = ofs_z; - packet.diag_x = diag_x; - packet.diag_y = diag_y; - packet.diag_z = diag_z; - packet.offdiag_x = offdiag_x; - packet.offdiag_y = offdiag_y; - packet.offdiag_z = offdiag_z; - packet.compass_id = compass_id; - packet.cal_mask = cal_mask; - packet.cal_status = cal_status; - packet.autosaved = autosaved; - packet.orientation_confidence = orientation_confidence; - packet.old_orientation = old_orientation; - packet.new_orientation = new_orientation; - packet.scale_factor = scale_factor; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MAG_CAL_REPORT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_MAG_CAL_REPORT; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MAG_CAL_REPORT_MIN_LEN, MAVLINK_MSG_ID_MAG_CAL_REPORT_LEN, MAVLINK_MSG_ID_MAG_CAL_REPORT_CRC); -} - -/** - * @brief Pack a mag_cal_report message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param compass_id Compass being calibrated. - * @param cal_mask Bitmask of compasses being calibrated. - * @param cal_status Calibration Status. - * @param autosaved 0=requires a MAV_CMD_DO_ACCEPT_MAG_CAL, 1=saved to parameters. - * @param fitness [mgauss] RMS milligauss residuals. - * @param ofs_x X offset. - * @param ofs_y Y offset. - * @param ofs_z Z offset. - * @param diag_x X diagonal (matrix 11). - * @param diag_y Y diagonal (matrix 22). - * @param diag_z Z diagonal (matrix 33). - * @param offdiag_x X off-diagonal (matrix 12 and 21). - * @param offdiag_y Y off-diagonal (matrix 13 and 31). - * @param offdiag_z Z off-diagonal (matrix 32 and 23). - * @param orientation_confidence Confidence in orientation (higher is better). - * @param old_orientation orientation before calibration. - * @param new_orientation orientation after calibration. - * @param scale_factor field radius correction factor - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_mag_cal_report_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t compass_id,uint8_t cal_mask,uint8_t cal_status,uint8_t autosaved,float fitness,float ofs_x,float ofs_y,float ofs_z,float diag_x,float diag_y,float diag_z,float offdiag_x,float offdiag_y,float offdiag_z,float orientation_confidence,uint8_t old_orientation,uint8_t new_orientation,float scale_factor) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MAG_CAL_REPORT_LEN]; - _mav_put_float(buf, 0, fitness); - _mav_put_float(buf, 4, ofs_x); - _mav_put_float(buf, 8, ofs_y); - _mav_put_float(buf, 12, ofs_z); - _mav_put_float(buf, 16, diag_x); - _mav_put_float(buf, 20, diag_y); - _mav_put_float(buf, 24, diag_z); - _mav_put_float(buf, 28, offdiag_x); - _mav_put_float(buf, 32, offdiag_y); - _mav_put_float(buf, 36, offdiag_z); - _mav_put_uint8_t(buf, 40, compass_id); - _mav_put_uint8_t(buf, 41, cal_mask); - _mav_put_uint8_t(buf, 42, cal_status); - _mav_put_uint8_t(buf, 43, autosaved); - _mav_put_float(buf, 44, orientation_confidence); - _mav_put_uint8_t(buf, 48, old_orientation); - _mav_put_uint8_t(buf, 49, new_orientation); - _mav_put_float(buf, 50, scale_factor); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MAG_CAL_REPORT_LEN); -#else - mavlink_mag_cal_report_t packet; - packet.fitness = fitness; - packet.ofs_x = ofs_x; - packet.ofs_y = ofs_y; - packet.ofs_z = ofs_z; - packet.diag_x = diag_x; - packet.diag_y = diag_y; - packet.diag_z = diag_z; - packet.offdiag_x = offdiag_x; - packet.offdiag_y = offdiag_y; - packet.offdiag_z = offdiag_z; - packet.compass_id = compass_id; - packet.cal_mask = cal_mask; - packet.cal_status = cal_status; - packet.autosaved = autosaved; - packet.orientation_confidence = orientation_confidence; - packet.old_orientation = old_orientation; - packet.new_orientation = new_orientation; - packet.scale_factor = scale_factor; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MAG_CAL_REPORT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_MAG_CAL_REPORT; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MAG_CAL_REPORT_MIN_LEN, MAVLINK_MSG_ID_MAG_CAL_REPORT_LEN, MAVLINK_MSG_ID_MAG_CAL_REPORT_CRC); -} - -/** - * @brief Encode a mag_cal_report struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param mag_cal_report C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_mag_cal_report_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mag_cal_report_t* mag_cal_report) -{ - return mavlink_msg_mag_cal_report_pack(system_id, component_id, msg, mag_cal_report->compass_id, mag_cal_report->cal_mask, mag_cal_report->cal_status, mag_cal_report->autosaved, mag_cal_report->fitness, mag_cal_report->ofs_x, mag_cal_report->ofs_y, mag_cal_report->ofs_z, mag_cal_report->diag_x, mag_cal_report->diag_y, mag_cal_report->diag_z, mag_cal_report->offdiag_x, mag_cal_report->offdiag_y, mag_cal_report->offdiag_z, mag_cal_report->orientation_confidence, mag_cal_report->old_orientation, mag_cal_report->new_orientation, mag_cal_report->scale_factor); -} - -/** - * @brief Encode a mag_cal_report struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param mag_cal_report C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_mag_cal_report_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mag_cal_report_t* mag_cal_report) -{ - return mavlink_msg_mag_cal_report_pack_chan(system_id, component_id, chan, msg, mag_cal_report->compass_id, mag_cal_report->cal_mask, mag_cal_report->cal_status, mag_cal_report->autosaved, mag_cal_report->fitness, mag_cal_report->ofs_x, mag_cal_report->ofs_y, mag_cal_report->ofs_z, mag_cal_report->diag_x, mag_cal_report->diag_y, mag_cal_report->diag_z, mag_cal_report->offdiag_x, mag_cal_report->offdiag_y, mag_cal_report->offdiag_z, mag_cal_report->orientation_confidence, mag_cal_report->old_orientation, mag_cal_report->new_orientation, mag_cal_report->scale_factor); -} - -/** - * @brief Send a mag_cal_report message - * @param chan MAVLink channel to send the message - * - * @param compass_id Compass being calibrated. - * @param cal_mask Bitmask of compasses being calibrated. - * @param cal_status Calibration Status. - * @param autosaved 0=requires a MAV_CMD_DO_ACCEPT_MAG_CAL, 1=saved to parameters. - * @param fitness [mgauss] RMS milligauss residuals. - * @param ofs_x X offset. - * @param ofs_y Y offset. - * @param ofs_z Z offset. - * @param diag_x X diagonal (matrix 11). - * @param diag_y Y diagonal (matrix 22). - * @param diag_z Z diagonal (matrix 33). - * @param offdiag_x X off-diagonal (matrix 12 and 21). - * @param offdiag_y Y off-diagonal (matrix 13 and 31). - * @param offdiag_z Z off-diagonal (matrix 32 and 23). - * @param orientation_confidence Confidence in orientation (higher is better). - * @param old_orientation orientation before calibration. - * @param new_orientation orientation after calibration. - * @param scale_factor field radius correction factor - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_mag_cal_report_send(mavlink_channel_t chan, uint8_t compass_id, uint8_t cal_mask, uint8_t cal_status, uint8_t autosaved, float fitness, float ofs_x, float ofs_y, float ofs_z, float diag_x, float diag_y, float diag_z, float offdiag_x, float offdiag_y, float offdiag_z, float orientation_confidence, uint8_t old_orientation, uint8_t new_orientation, float scale_factor) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MAG_CAL_REPORT_LEN]; - _mav_put_float(buf, 0, fitness); - _mav_put_float(buf, 4, ofs_x); - _mav_put_float(buf, 8, ofs_y); - _mav_put_float(buf, 12, ofs_z); - _mav_put_float(buf, 16, diag_x); - _mav_put_float(buf, 20, diag_y); - _mav_put_float(buf, 24, diag_z); - _mav_put_float(buf, 28, offdiag_x); - _mav_put_float(buf, 32, offdiag_y); - _mav_put_float(buf, 36, offdiag_z); - _mav_put_uint8_t(buf, 40, compass_id); - _mav_put_uint8_t(buf, 41, cal_mask); - _mav_put_uint8_t(buf, 42, cal_status); - _mav_put_uint8_t(buf, 43, autosaved); - _mav_put_float(buf, 44, orientation_confidence); - _mav_put_uint8_t(buf, 48, old_orientation); - _mav_put_uint8_t(buf, 49, new_orientation); - _mav_put_float(buf, 50, scale_factor); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MAG_CAL_REPORT, buf, MAVLINK_MSG_ID_MAG_CAL_REPORT_MIN_LEN, MAVLINK_MSG_ID_MAG_CAL_REPORT_LEN, MAVLINK_MSG_ID_MAG_CAL_REPORT_CRC); -#else - mavlink_mag_cal_report_t packet; - packet.fitness = fitness; - packet.ofs_x = ofs_x; - packet.ofs_y = ofs_y; - packet.ofs_z = ofs_z; - packet.diag_x = diag_x; - packet.diag_y = diag_y; - packet.diag_z = diag_z; - packet.offdiag_x = offdiag_x; - packet.offdiag_y = offdiag_y; - packet.offdiag_z = offdiag_z; - packet.compass_id = compass_id; - packet.cal_mask = cal_mask; - packet.cal_status = cal_status; - packet.autosaved = autosaved; - packet.orientation_confidence = orientation_confidence; - packet.old_orientation = old_orientation; - packet.new_orientation = new_orientation; - packet.scale_factor = scale_factor; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MAG_CAL_REPORT, (const char *)&packet, MAVLINK_MSG_ID_MAG_CAL_REPORT_MIN_LEN, MAVLINK_MSG_ID_MAG_CAL_REPORT_LEN, MAVLINK_MSG_ID_MAG_CAL_REPORT_CRC); -#endif -} - -/** - * @brief Send a mag_cal_report message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_mag_cal_report_send_struct(mavlink_channel_t chan, const mavlink_mag_cal_report_t* mag_cal_report) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_mag_cal_report_send(chan, mag_cal_report->compass_id, mag_cal_report->cal_mask, mag_cal_report->cal_status, mag_cal_report->autosaved, mag_cal_report->fitness, mag_cal_report->ofs_x, mag_cal_report->ofs_y, mag_cal_report->ofs_z, mag_cal_report->diag_x, mag_cal_report->diag_y, mag_cal_report->diag_z, mag_cal_report->offdiag_x, mag_cal_report->offdiag_y, mag_cal_report->offdiag_z, mag_cal_report->orientation_confidence, mag_cal_report->old_orientation, mag_cal_report->new_orientation, mag_cal_report->scale_factor); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MAG_CAL_REPORT, (const char *)mag_cal_report, MAVLINK_MSG_ID_MAG_CAL_REPORT_MIN_LEN, MAVLINK_MSG_ID_MAG_CAL_REPORT_LEN, MAVLINK_MSG_ID_MAG_CAL_REPORT_CRC); -#endif -} - -#if MAVLINK_MSG_ID_MAG_CAL_REPORT_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_mag_cal_report_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t compass_id, uint8_t cal_mask, uint8_t cal_status, uint8_t autosaved, float fitness, float ofs_x, float ofs_y, float ofs_z, float diag_x, float diag_y, float diag_z, float offdiag_x, float offdiag_y, float offdiag_z, float orientation_confidence, uint8_t old_orientation, uint8_t new_orientation, float scale_factor) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_float(buf, 0, fitness); - _mav_put_float(buf, 4, ofs_x); - _mav_put_float(buf, 8, ofs_y); - _mav_put_float(buf, 12, ofs_z); - _mav_put_float(buf, 16, diag_x); - _mav_put_float(buf, 20, diag_y); - _mav_put_float(buf, 24, diag_z); - _mav_put_float(buf, 28, offdiag_x); - _mav_put_float(buf, 32, offdiag_y); - _mav_put_float(buf, 36, offdiag_z); - _mav_put_uint8_t(buf, 40, compass_id); - _mav_put_uint8_t(buf, 41, cal_mask); - _mav_put_uint8_t(buf, 42, cal_status); - _mav_put_uint8_t(buf, 43, autosaved); - _mav_put_float(buf, 44, orientation_confidence); - _mav_put_uint8_t(buf, 48, old_orientation); - _mav_put_uint8_t(buf, 49, new_orientation); - _mav_put_float(buf, 50, scale_factor); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MAG_CAL_REPORT, buf, MAVLINK_MSG_ID_MAG_CAL_REPORT_MIN_LEN, MAVLINK_MSG_ID_MAG_CAL_REPORT_LEN, MAVLINK_MSG_ID_MAG_CAL_REPORT_CRC); -#else - mavlink_mag_cal_report_t *packet = (mavlink_mag_cal_report_t *)msgbuf; - packet->fitness = fitness; - packet->ofs_x = ofs_x; - packet->ofs_y = ofs_y; - packet->ofs_z = ofs_z; - packet->diag_x = diag_x; - packet->diag_y = diag_y; - packet->diag_z = diag_z; - packet->offdiag_x = offdiag_x; - packet->offdiag_y = offdiag_y; - packet->offdiag_z = offdiag_z; - packet->compass_id = compass_id; - packet->cal_mask = cal_mask; - packet->cal_status = cal_status; - packet->autosaved = autosaved; - packet->orientation_confidence = orientation_confidence; - packet->old_orientation = old_orientation; - packet->new_orientation = new_orientation; - packet->scale_factor = scale_factor; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MAG_CAL_REPORT, (const char *)packet, MAVLINK_MSG_ID_MAG_CAL_REPORT_MIN_LEN, MAVLINK_MSG_ID_MAG_CAL_REPORT_LEN, MAVLINK_MSG_ID_MAG_CAL_REPORT_CRC); -#endif -} -#endif - -#endif - -// MESSAGE MAG_CAL_REPORT UNPACKING - - -/** - * @brief Get field compass_id from mag_cal_report message - * - * @return Compass being calibrated. - */ -static inline uint8_t mavlink_msg_mag_cal_report_get_compass_id(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 40); -} - -/** - * @brief Get field cal_mask from mag_cal_report message - * - * @return Bitmask of compasses being calibrated. - */ -static inline uint8_t mavlink_msg_mag_cal_report_get_cal_mask(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 41); -} - -/** - * @brief Get field cal_status from mag_cal_report message - * - * @return Calibration Status. - */ -static inline uint8_t mavlink_msg_mag_cal_report_get_cal_status(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 42); -} - -/** - * @brief Get field autosaved from mag_cal_report message - * - * @return 0=requires a MAV_CMD_DO_ACCEPT_MAG_CAL, 1=saved to parameters. - */ -static inline uint8_t mavlink_msg_mag_cal_report_get_autosaved(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 43); -} - -/** - * @brief Get field fitness from mag_cal_report message - * - * @return [mgauss] RMS milligauss residuals. - */ -static inline float mavlink_msg_mag_cal_report_get_fitness(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 0); -} - -/** - * @brief Get field ofs_x from mag_cal_report message - * - * @return X offset. - */ -static inline float mavlink_msg_mag_cal_report_get_ofs_x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 4); -} - -/** - * @brief Get field ofs_y from mag_cal_report message - * - * @return Y offset. - */ -static inline float mavlink_msg_mag_cal_report_get_ofs_y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field ofs_z from mag_cal_report message - * - * @return Z offset. - */ -static inline float mavlink_msg_mag_cal_report_get_ofs_z(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field diag_x from mag_cal_report message - * - * @return X diagonal (matrix 11). - */ -static inline float mavlink_msg_mag_cal_report_get_diag_x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field diag_y from mag_cal_report message - * - * @return Y diagonal (matrix 22). - */ -static inline float mavlink_msg_mag_cal_report_get_diag_y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Get field diag_z from mag_cal_report message - * - * @return Z diagonal (matrix 33). - */ -static inline float mavlink_msg_mag_cal_report_get_diag_z(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Get field offdiag_x from mag_cal_report message - * - * @return X off-diagonal (matrix 12 and 21). - */ -static inline float mavlink_msg_mag_cal_report_get_offdiag_x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 28); -} - -/** - * @brief Get field offdiag_y from mag_cal_report message - * - * @return Y off-diagonal (matrix 13 and 31). - */ -static inline float mavlink_msg_mag_cal_report_get_offdiag_y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 32); -} - -/** - * @brief Get field offdiag_z from mag_cal_report message - * - * @return Z off-diagonal (matrix 32 and 23). - */ -static inline float mavlink_msg_mag_cal_report_get_offdiag_z(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 36); -} - -/** - * @brief Get field orientation_confidence from mag_cal_report message - * - * @return Confidence in orientation (higher is better). - */ -static inline float mavlink_msg_mag_cal_report_get_orientation_confidence(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 44); -} - -/** - * @brief Get field old_orientation from mag_cal_report message - * - * @return orientation before calibration. - */ -static inline uint8_t mavlink_msg_mag_cal_report_get_old_orientation(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 48); -} - -/** - * @brief Get field new_orientation from mag_cal_report message - * - * @return orientation after calibration. - */ -static inline uint8_t mavlink_msg_mag_cal_report_get_new_orientation(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 49); -} - -/** - * @brief Get field scale_factor from mag_cal_report message - * - * @return field radius correction factor - */ -static inline float mavlink_msg_mag_cal_report_get_scale_factor(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 50); -} - -/** - * @brief Decode a mag_cal_report message into a struct - * - * @param msg The message to decode - * @param mag_cal_report C-struct to decode the message contents into - */ -static inline void mavlink_msg_mag_cal_report_decode(const mavlink_message_t* msg, mavlink_mag_cal_report_t* mag_cal_report) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mag_cal_report->fitness = mavlink_msg_mag_cal_report_get_fitness(msg); - mag_cal_report->ofs_x = mavlink_msg_mag_cal_report_get_ofs_x(msg); - mag_cal_report->ofs_y = mavlink_msg_mag_cal_report_get_ofs_y(msg); - mag_cal_report->ofs_z = mavlink_msg_mag_cal_report_get_ofs_z(msg); - mag_cal_report->diag_x = mavlink_msg_mag_cal_report_get_diag_x(msg); - mag_cal_report->diag_y = mavlink_msg_mag_cal_report_get_diag_y(msg); - mag_cal_report->diag_z = mavlink_msg_mag_cal_report_get_diag_z(msg); - mag_cal_report->offdiag_x = mavlink_msg_mag_cal_report_get_offdiag_x(msg); - mag_cal_report->offdiag_y = mavlink_msg_mag_cal_report_get_offdiag_y(msg); - mag_cal_report->offdiag_z = mavlink_msg_mag_cal_report_get_offdiag_z(msg); - mag_cal_report->compass_id = mavlink_msg_mag_cal_report_get_compass_id(msg); - mag_cal_report->cal_mask = mavlink_msg_mag_cal_report_get_cal_mask(msg); - mag_cal_report->cal_status = mavlink_msg_mag_cal_report_get_cal_status(msg); - mag_cal_report->autosaved = mavlink_msg_mag_cal_report_get_autosaved(msg); - mag_cal_report->orientation_confidence = mavlink_msg_mag_cal_report_get_orientation_confidence(msg); - mag_cal_report->old_orientation = mavlink_msg_mag_cal_report_get_old_orientation(msg); - mag_cal_report->new_orientation = mavlink_msg_mag_cal_report_get_new_orientation(msg); - mag_cal_report->scale_factor = mavlink_msg_mag_cal_report_get_scale_factor(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_MAG_CAL_REPORT_LEN? msg->len : MAVLINK_MSG_ID_MAG_CAL_REPORT_LEN; - memset(mag_cal_report, 0, MAVLINK_MSG_ID_MAG_CAL_REPORT_LEN); - memcpy(mag_cal_report, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_manual_control.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_manual_control.h deleted file mode 100644 index 44554285..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_manual_control.h +++ /dev/null @@ -1,438 +0,0 @@ -#pragma once -// MESSAGE MANUAL_CONTROL PACKING - -#define MAVLINK_MSG_ID_MANUAL_CONTROL 69 - -MAVPACKED( -typedef struct __mavlink_manual_control_t { - int16_t x; /*< X-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to forward(1000)-backward(-1000) movement on a joystick and the pitch of a vehicle.*/ - int16_t y; /*< Y-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to left(-1000)-right(1000) movement on a joystick and the roll of a vehicle.*/ - int16_t z; /*< Z-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a separate slider movement with maximum being 1000 and minimum being -1000 on a joystick and the thrust of a vehicle. Positive values are positive thrust, negative values are negative thrust.*/ - int16_t r; /*< R-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a twisting of the joystick, with counter-clockwise being 1000 and clockwise being -1000, and the yaw of a vehicle.*/ - uint16_t buttons; /*< A bitfield corresponding to the joystick buttons' 0-15 current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 1.*/ - uint8_t target; /*< The system to be controlled.*/ - uint16_t buttons2; /*< A bitfield corresponding to the joystick buttons' 16-31 current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 16.*/ - uint8_t enabled_extensions; /*< Set bits to 1 to indicate which of the following extension fields contain valid data: bit 0: pitch, bit 1: roll.*/ - int16_t s; /*< Pitch-only-axis, normalized to the range [-1000,1000]. Generally corresponds to pitch on vehicles with additional degrees of freedom. Valid if bit 0 of enabled_extensions field is set. Set to 0 if invalid.*/ - int16_t t; /*< Roll-only-axis, normalized to the range [-1000,1000]. Generally corresponds to roll on vehicles with additional degrees of freedom. Valid if bit 1 of enabled_extensions field is set. Set to 0 if invalid.*/ -}) mavlink_manual_control_t; - -#define MAVLINK_MSG_ID_MANUAL_CONTROL_LEN 18 -#define MAVLINK_MSG_ID_MANUAL_CONTROL_MIN_LEN 11 -#define MAVLINK_MSG_ID_69_LEN 18 -#define MAVLINK_MSG_ID_69_MIN_LEN 11 - -#define MAVLINK_MSG_ID_MANUAL_CONTROL_CRC 243 -#define MAVLINK_MSG_ID_69_CRC 243 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_MANUAL_CONTROL { \ - 69, \ - "MANUAL_CONTROL", \ - 10, \ - { { "target", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_manual_control_t, target) }, \ - { "x", NULL, MAVLINK_TYPE_INT16_T, 0, 0, offsetof(mavlink_manual_control_t, x) }, \ - { "y", NULL, MAVLINK_TYPE_INT16_T, 0, 2, offsetof(mavlink_manual_control_t, y) }, \ - { "z", NULL, MAVLINK_TYPE_INT16_T, 0, 4, offsetof(mavlink_manual_control_t, z) }, \ - { "r", NULL, MAVLINK_TYPE_INT16_T, 0, 6, offsetof(mavlink_manual_control_t, r) }, \ - { "buttons", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_manual_control_t, buttons) }, \ - { "buttons2", NULL, MAVLINK_TYPE_UINT16_T, 0, 11, offsetof(mavlink_manual_control_t, buttons2) }, \ - { "enabled_extensions", NULL, MAVLINK_TYPE_UINT8_T, 0, 13, offsetof(mavlink_manual_control_t, enabled_extensions) }, \ - { "s", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_manual_control_t, s) }, \ - { "t", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_manual_control_t, t) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_MANUAL_CONTROL { \ - "MANUAL_CONTROL", \ - 10, \ - { { "target", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_manual_control_t, target) }, \ - { "x", NULL, MAVLINK_TYPE_INT16_T, 0, 0, offsetof(mavlink_manual_control_t, x) }, \ - { "y", NULL, MAVLINK_TYPE_INT16_T, 0, 2, offsetof(mavlink_manual_control_t, y) }, \ - { "z", NULL, MAVLINK_TYPE_INT16_T, 0, 4, offsetof(mavlink_manual_control_t, z) }, \ - { "r", NULL, MAVLINK_TYPE_INT16_T, 0, 6, offsetof(mavlink_manual_control_t, r) }, \ - { "buttons", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_manual_control_t, buttons) }, \ - { "buttons2", NULL, MAVLINK_TYPE_UINT16_T, 0, 11, offsetof(mavlink_manual_control_t, buttons2) }, \ - { "enabled_extensions", NULL, MAVLINK_TYPE_UINT8_T, 0, 13, offsetof(mavlink_manual_control_t, enabled_extensions) }, \ - { "s", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_manual_control_t, s) }, \ - { "t", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_manual_control_t, t) }, \ - } \ -} -#endif - -/** - * @brief Pack a manual_control message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target The system to be controlled. - * @param x X-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to forward(1000)-backward(-1000) movement on a joystick and the pitch of a vehicle. - * @param y Y-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to left(-1000)-right(1000) movement on a joystick and the roll of a vehicle. - * @param z Z-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a separate slider movement with maximum being 1000 and minimum being -1000 on a joystick and the thrust of a vehicle. Positive values are positive thrust, negative values are negative thrust. - * @param r R-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a twisting of the joystick, with counter-clockwise being 1000 and clockwise being -1000, and the yaw of a vehicle. - * @param buttons A bitfield corresponding to the joystick buttons' 0-15 current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 1. - * @param buttons2 A bitfield corresponding to the joystick buttons' 16-31 current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 16. - * @param enabled_extensions Set bits to 1 to indicate which of the following extension fields contain valid data: bit 0: pitch, bit 1: roll. - * @param s Pitch-only-axis, normalized to the range [-1000,1000]. Generally corresponds to pitch on vehicles with additional degrees of freedom. Valid if bit 0 of enabled_extensions field is set. Set to 0 if invalid. - * @param t Roll-only-axis, normalized to the range [-1000,1000]. Generally corresponds to roll on vehicles with additional degrees of freedom. Valid if bit 1 of enabled_extensions field is set. Set to 0 if invalid. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_manual_control_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target, int16_t x, int16_t y, int16_t z, int16_t r, uint16_t buttons, uint16_t buttons2, uint8_t enabled_extensions, int16_t s, int16_t t) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MANUAL_CONTROL_LEN]; - _mav_put_int16_t(buf, 0, x); - _mav_put_int16_t(buf, 2, y); - _mav_put_int16_t(buf, 4, z); - _mav_put_int16_t(buf, 6, r); - _mav_put_uint16_t(buf, 8, buttons); - _mav_put_uint8_t(buf, 10, target); - _mav_put_uint16_t(buf, 11, buttons2); - _mav_put_uint8_t(buf, 13, enabled_extensions); - _mav_put_int16_t(buf, 14, s); - _mav_put_int16_t(buf, 16, t); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MANUAL_CONTROL_LEN); -#else - mavlink_manual_control_t packet; - packet.x = x; - packet.y = y; - packet.z = z; - packet.r = r; - packet.buttons = buttons; - packet.target = target; - packet.buttons2 = buttons2; - packet.enabled_extensions = enabled_extensions; - packet.s = s; - packet.t = t; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MANUAL_CONTROL_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_MANUAL_CONTROL; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MANUAL_CONTROL_MIN_LEN, MAVLINK_MSG_ID_MANUAL_CONTROL_LEN, MAVLINK_MSG_ID_MANUAL_CONTROL_CRC); -} - -/** - * @brief Pack a manual_control message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target The system to be controlled. - * @param x X-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to forward(1000)-backward(-1000) movement on a joystick and the pitch of a vehicle. - * @param y Y-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to left(-1000)-right(1000) movement on a joystick and the roll of a vehicle. - * @param z Z-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a separate slider movement with maximum being 1000 and minimum being -1000 on a joystick and the thrust of a vehicle. Positive values are positive thrust, negative values are negative thrust. - * @param r R-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a twisting of the joystick, with counter-clockwise being 1000 and clockwise being -1000, and the yaw of a vehicle. - * @param buttons A bitfield corresponding to the joystick buttons' 0-15 current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 1. - * @param buttons2 A bitfield corresponding to the joystick buttons' 16-31 current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 16. - * @param enabled_extensions Set bits to 1 to indicate which of the following extension fields contain valid data: bit 0: pitch, bit 1: roll. - * @param s Pitch-only-axis, normalized to the range [-1000,1000]. Generally corresponds to pitch on vehicles with additional degrees of freedom. Valid if bit 0 of enabled_extensions field is set. Set to 0 if invalid. - * @param t Roll-only-axis, normalized to the range [-1000,1000]. Generally corresponds to roll on vehicles with additional degrees of freedom. Valid if bit 1 of enabled_extensions field is set. Set to 0 if invalid. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_manual_control_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target,int16_t x,int16_t y,int16_t z,int16_t r,uint16_t buttons,uint16_t buttons2,uint8_t enabled_extensions,int16_t s,int16_t t) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MANUAL_CONTROL_LEN]; - _mav_put_int16_t(buf, 0, x); - _mav_put_int16_t(buf, 2, y); - _mav_put_int16_t(buf, 4, z); - _mav_put_int16_t(buf, 6, r); - _mav_put_uint16_t(buf, 8, buttons); - _mav_put_uint8_t(buf, 10, target); - _mav_put_uint16_t(buf, 11, buttons2); - _mav_put_uint8_t(buf, 13, enabled_extensions); - _mav_put_int16_t(buf, 14, s); - _mav_put_int16_t(buf, 16, t); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MANUAL_CONTROL_LEN); -#else - mavlink_manual_control_t packet; - packet.x = x; - packet.y = y; - packet.z = z; - packet.r = r; - packet.buttons = buttons; - packet.target = target; - packet.buttons2 = buttons2; - packet.enabled_extensions = enabled_extensions; - packet.s = s; - packet.t = t; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MANUAL_CONTROL_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_MANUAL_CONTROL; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MANUAL_CONTROL_MIN_LEN, MAVLINK_MSG_ID_MANUAL_CONTROL_LEN, MAVLINK_MSG_ID_MANUAL_CONTROL_CRC); -} - -/** - * @brief Encode a manual_control struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param manual_control C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_manual_control_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_manual_control_t* manual_control) -{ - return mavlink_msg_manual_control_pack(system_id, component_id, msg, manual_control->target, manual_control->x, manual_control->y, manual_control->z, manual_control->r, manual_control->buttons, manual_control->buttons2, manual_control->enabled_extensions, manual_control->s, manual_control->t); -} - -/** - * @brief Encode a manual_control struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param manual_control C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_manual_control_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_manual_control_t* manual_control) -{ - return mavlink_msg_manual_control_pack_chan(system_id, component_id, chan, msg, manual_control->target, manual_control->x, manual_control->y, manual_control->z, manual_control->r, manual_control->buttons, manual_control->buttons2, manual_control->enabled_extensions, manual_control->s, manual_control->t); -} - -/** - * @brief Send a manual_control message - * @param chan MAVLink channel to send the message - * - * @param target The system to be controlled. - * @param x X-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to forward(1000)-backward(-1000) movement on a joystick and the pitch of a vehicle. - * @param y Y-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to left(-1000)-right(1000) movement on a joystick and the roll of a vehicle. - * @param z Z-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a separate slider movement with maximum being 1000 and minimum being -1000 on a joystick and the thrust of a vehicle. Positive values are positive thrust, negative values are negative thrust. - * @param r R-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a twisting of the joystick, with counter-clockwise being 1000 and clockwise being -1000, and the yaw of a vehicle. - * @param buttons A bitfield corresponding to the joystick buttons' 0-15 current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 1. - * @param buttons2 A bitfield corresponding to the joystick buttons' 16-31 current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 16. - * @param enabled_extensions Set bits to 1 to indicate which of the following extension fields contain valid data: bit 0: pitch, bit 1: roll. - * @param s Pitch-only-axis, normalized to the range [-1000,1000]. Generally corresponds to pitch on vehicles with additional degrees of freedom. Valid if bit 0 of enabled_extensions field is set. Set to 0 if invalid. - * @param t Roll-only-axis, normalized to the range [-1000,1000]. Generally corresponds to roll on vehicles with additional degrees of freedom. Valid if bit 1 of enabled_extensions field is set. Set to 0 if invalid. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_manual_control_send(mavlink_channel_t chan, uint8_t target, int16_t x, int16_t y, int16_t z, int16_t r, uint16_t buttons, uint16_t buttons2, uint8_t enabled_extensions, int16_t s, int16_t t) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MANUAL_CONTROL_LEN]; - _mav_put_int16_t(buf, 0, x); - _mav_put_int16_t(buf, 2, y); - _mav_put_int16_t(buf, 4, z); - _mav_put_int16_t(buf, 6, r); - _mav_put_uint16_t(buf, 8, buttons); - _mav_put_uint8_t(buf, 10, target); - _mav_put_uint16_t(buf, 11, buttons2); - _mav_put_uint8_t(buf, 13, enabled_extensions); - _mav_put_int16_t(buf, 14, s); - _mav_put_int16_t(buf, 16, t); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MANUAL_CONTROL, buf, MAVLINK_MSG_ID_MANUAL_CONTROL_MIN_LEN, MAVLINK_MSG_ID_MANUAL_CONTROL_LEN, MAVLINK_MSG_ID_MANUAL_CONTROL_CRC); -#else - mavlink_manual_control_t packet; - packet.x = x; - packet.y = y; - packet.z = z; - packet.r = r; - packet.buttons = buttons; - packet.target = target; - packet.buttons2 = buttons2; - packet.enabled_extensions = enabled_extensions; - packet.s = s; - packet.t = t; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MANUAL_CONTROL, (const char *)&packet, MAVLINK_MSG_ID_MANUAL_CONTROL_MIN_LEN, MAVLINK_MSG_ID_MANUAL_CONTROL_LEN, MAVLINK_MSG_ID_MANUAL_CONTROL_CRC); -#endif -} - -/** - * @brief Send a manual_control message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_manual_control_send_struct(mavlink_channel_t chan, const mavlink_manual_control_t* manual_control) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_manual_control_send(chan, manual_control->target, manual_control->x, manual_control->y, manual_control->z, manual_control->r, manual_control->buttons, manual_control->buttons2, manual_control->enabled_extensions, manual_control->s, manual_control->t); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MANUAL_CONTROL, (const char *)manual_control, MAVLINK_MSG_ID_MANUAL_CONTROL_MIN_LEN, MAVLINK_MSG_ID_MANUAL_CONTROL_LEN, MAVLINK_MSG_ID_MANUAL_CONTROL_CRC); -#endif -} - -#if MAVLINK_MSG_ID_MANUAL_CONTROL_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_manual_control_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target, int16_t x, int16_t y, int16_t z, int16_t r, uint16_t buttons, uint16_t buttons2, uint8_t enabled_extensions, int16_t s, int16_t t) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_int16_t(buf, 0, x); - _mav_put_int16_t(buf, 2, y); - _mav_put_int16_t(buf, 4, z); - _mav_put_int16_t(buf, 6, r); - _mav_put_uint16_t(buf, 8, buttons); - _mav_put_uint8_t(buf, 10, target); - _mav_put_uint16_t(buf, 11, buttons2); - _mav_put_uint8_t(buf, 13, enabled_extensions); - _mav_put_int16_t(buf, 14, s); - _mav_put_int16_t(buf, 16, t); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MANUAL_CONTROL, buf, MAVLINK_MSG_ID_MANUAL_CONTROL_MIN_LEN, MAVLINK_MSG_ID_MANUAL_CONTROL_LEN, MAVLINK_MSG_ID_MANUAL_CONTROL_CRC); -#else - mavlink_manual_control_t *packet = (mavlink_manual_control_t *)msgbuf; - packet->x = x; - packet->y = y; - packet->z = z; - packet->r = r; - packet->buttons = buttons; - packet->target = target; - packet->buttons2 = buttons2; - packet->enabled_extensions = enabled_extensions; - packet->s = s; - packet->t = t; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MANUAL_CONTROL, (const char *)packet, MAVLINK_MSG_ID_MANUAL_CONTROL_MIN_LEN, MAVLINK_MSG_ID_MANUAL_CONTROL_LEN, MAVLINK_MSG_ID_MANUAL_CONTROL_CRC); -#endif -} -#endif - -#endif - -// MESSAGE MANUAL_CONTROL UNPACKING - - -/** - * @brief Get field target from manual_control message - * - * @return The system to be controlled. - */ -static inline uint8_t mavlink_msg_manual_control_get_target(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 10); -} - -/** - * @brief Get field x from manual_control message - * - * @return X-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to forward(1000)-backward(-1000) movement on a joystick and the pitch of a vehicle. - */ -static inline int16_t mavlink_msg_manual_control_get_x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 0); -} - -/** - * @brief Get field y from manual_control message - * - * @return Y-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to left(-1000)-right(1000) movement on a joystick and the roll of a vehicle. - */ -static inline int16_t mavlink_msg_manual_control_get_y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 2); -} - -/** - * @brief Get field z from manual_control message - * - * @return Z-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a separate slider movement with maximum being 1000 and minimum being -1000 on a joystick and the thrust of a vehicle. Positive values are positive thrust, negative values are negative thrust. - */ -static inline int16_t mavlink_msg_manual_control_get_z(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 4); -} - -/** - * @brief Get field r from manual_control message - * - * @return R-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a twisting of the joystick, with counter-clockwise being 1000 and clockwise being -1000, and the yaw of a vehicle. - */ -static inline int16_t mavlink_msg_manual_control_get_r(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 6); -} - -/** - * @brief Get field buttons from manual_control message - * - * @return A bitfield corresponding to the joystick buttons' 0-15 current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 1. - */ -static inline uint16_t mavlink_msg_manual_control_get_buttons(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 8); -} - -/** - * @brief Get field buttons2 from manual_control message - * - * @return A bitfield corresponding to the joystick buttons' 16-31 current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 16. - */ -static inline uint16_t mavlink_msg_manual_control_get_buttons2(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 11); -} - -/** - * @brief Get field enabled_extensions from manual_control message - * - * @return Set bits to 1 to indicate which of the following extension fields contain valid data: bit 0: pitch, bit 1: roll. - */ -static inline uint8_t mavlink_msg_manual_control_get_enabled_extensions(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 13); -} - -/** - * @brief Get field s from manual_control message - * - * @return Pitch-only-axis, normalized to the range [-1000,1000]. Generally corresponds to pitch on vehicles with additional degrees of freedom. Valid if bit 0 of enabled_extensions field is set. Set to 0 if invalid. - */ -static inline int16_t mavlink_msg_manual_control_get_s(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 14); -} - -/** - * @brief Get field t from manual_control message - * - * @return Roll-only-axis, normalized to the range [-1000,1000]. Generally corresponds to roll on vehicles with additional degrees of freedom. Valid if bit 1 of enabled_extensions field is set. Set to 0 if invalid. - */ -static inline int16_t mavlink_msg_manual_control_get_t(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 16); -} - -/** - * @brief Decode a manual_control message into a struct - * - * @param msg The message to decode - * @param manual_control C-struct to decode the message contents into - */ -static inline void mavlink_msg_manual_control_decode(const mavlink_message_t* msg, mavlink_manual_control_t* manual_control) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - manual_control->x = mavlink_msg_manual_control_get_x(msg); - manual_control->y = mavlink_msg_manual_control_get_y(msg); - manual_control->z = mavlink_msg_manual_control_get_z(msg); - manual_control->r = mavlink_msg_manual_control_get_r(msg); - manual_control->buttons = mavlink_msg_manual_control_get_buttons(msg); - manual_control->target = mavlink_msg_manual_control_get_target(msg); - manual_control->buttons2 = mavlink_msg_manual_control_get_buttons2(msg); - manual_control->enabled_extensions = mavlink_msg_manual_control_get_enabled_extensions(msg); - manual_control->s = mavlink_msg_manual_control_get_s(msg); - manual_control->t = mavlink_msg_manual_control_get_t(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_MANUAL_CONTROL_LEN? msg->len : MAVLINK_MSG_ID_MANUAL_CONTROL_LEN; - memset(manual_control, 0, MAVLINK_MSG_ID_MANUAL_CONTROL_LEN); - memcpy(manual_control, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_manual_setpoint.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_manual_setpoint.h deleted file mode 100644 index 09e5041c..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_manual_setpoint.h +++ /dev/null @@ -1,363 +0,0 @@ -#pragma once -// MESSAGE MANUAL_SETPOINT PACKING - -#define MAVLINK_MSG_ID_MANUAL_SETPOINT 81 - - -typedef struct __mavlink_manual_setpoint_t { - uint32_t time_boot_ms; /*< [ms] Timestamp (time since system boot).*/ - float roll; /*< [rad/s] Desired roll rate*/ - float pitch; /*< [rad/s] Desired pitch rate*/ - float yaw; /*< [rad/s] Desired yaw rate*/ - float thrust; /*< Collective thrust, normalized to 0 .. 1*/ - uint8_t mode_switch; /*< Flight mode switch position, 0.. 255*/ - uint8_t manual_override_switch; /*< Override mode switch position, 0.. 255*/ -} mavlink_manual_setpoint_t; - -#define MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN 22 -#define MAVLINK_MSG_ID_MANUAL_SETPOINT_MIN_LEN 22 -#define MAVLINK_MSG_ID_81_LEN 22 -#define MAVLINK_MSG_ID_81_MIN_LEN 22 - -#define MAVLINK_MSG_ID_MANUAL_SETPOINT_CRC 106 -#define MAVLINK_MSG_ID_81_CRC 106 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_MANUAL_SETPOINT { \ - 81, \ - "MANUAL_SETPOINT", \ - 7, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_manual_setpoint_t, time_boot_ms) }, \ - { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_manual_setpoint_t, roll) }, \ - { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_manual_setpoint_t, pitch) }, \ - { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_manual_setpoint_t, yaw) }, \ - { "thrust", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_manual_setpoint_t, thrust) }, \ - { "mode_switch", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_manual_setpoint_t, mode_switch) }, \ - { "manual_override_switch", NULL, MAVLINK_TYPE_UINT8_T, 0, 21, offsetof(mavlink_manual_setpoint_t, manual_override_switch) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_MANUAL_SETPOINT { \ - "MANUAL_SETPOINT", \ - 7, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_manual_setpoint_t, time_boot_ms) }, \ - { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_manual_setpoint_t, roll) }, \ - { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_manual_setpoint_t, pitch) }, \ - { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_manual_setpoint_t, yaw) }, \ - { "thrust", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_manual_setpoint_t, thrust) }, \ - { "mode_switch", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_manual_setpoint_t, mode_switch) }, \ - { "manual_override_switch", NULL, MAVLINK_TYPE_UINT8_T, 0, 21, offsetof(mavlink_manual_setpoint_t, manual_override_switch) }, \ - } \ -} -#endif - -/** - * @brief Pack a manual_setpoint message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param time_boot_ms [ms] Timestamp (time since system boot). - * @param roll [rad/s] Desired roll rate - * @param pitch [rad/s] Desired pitch rate - * @param yaw [rad/s] Desired yaw rate - * @param thrust Collective thrust, normalized to 0 .. 1 - * @param mode_switch Flight mode switch position, 0.. 255 - * @param manual_override_switch Override mode switch position, 0.. 255 - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_manual_setpoint_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint32_t time_boot_ms, float roll, float pitch, float yaw, float thrust, uint8_t mode_switch, uint8_t manual_override_switch) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, roll); - _mav_put_float(buf, 8, pitch); - _mav_put_float(buf, 12, yaw); - _mav_put_float(buf, 16, thrust); - _mav_put_uint8_t(buf, 20, mode_switch); - _mav_put_uint8_t(buf, 21, manual_override_switch); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN); -#else - mavlink_manual_setpoint_t packet; - packet.time_boot_ms = time_boot_ms; - packet.roll = roll; - packet.pitch = pitch; - packet.yaw = yaw; - packet.thrust = thrust; - packet.mode_switch = mode_switch; - packet.manual_override_switch = manual_override_switch; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_MANUAL_SETPOINT; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MANUAL_SETPOINT_MIN_LEN, MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN, MAVLINK_MSG_ID_MANUAL_SETPOINT_CRC); -} - -/** - * @brief Pack a manual_setpoint message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_boot_ms [ms] Timestamp (time since system boot). - * @param roll [rad/s] Desired roll rate - * @param pitch [rad/s] Desired pitch rate - * @param yaw [rad/s] Desired yaw rate - * @param thrust Collective thrust, normalized to 0 .. 1 - * @param mode_switch Flight mode switch position, 0.. 255 - * @param manual_override_switch Override mode switch position, 0.. 255 - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_manual_setpoint_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint32_t time_boot_ms,float roll,float pitch,float yaw,float thrust,uint8_t mode_switch,uint8_t manual_override_switch) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, roll); - _mav_put_float(buf, 8, pitch); - _mav_put_float(buf, 12, yaw); - _mav_put_float(buf, 16, thrust); - _mav_put_uint8_t(buf, 20, mode_switch); - _mav_put_uint8_t(buf, 21, manual_override_switch); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN); -#else - mavlink_manual_setpoint_t packet; - packet.time_boot_ms = time_boot_ms; - packet.roll = roll; - packet.pitch = pitch; - packet.yaw = yaw; - packet.thrust = thrust; - packet.mode_switch = mode_switch; - packet.manual_override_switch = manual_override_switch; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_MANUAL_SETPOINT; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MANUAL_SETPOINT_MIN_LEN, MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN, MAVLINK_MSG_ID_MANUAL_SETPOINT_CRC); -} - -/** - * @brief Encode a manual_setpoint struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param manual_setpoint C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_manual_setpoint_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_manual_setpoint_t* manual_setpoint) -{ - return mavlink_msg_manual_setpoint_pack(system_id, component_id, msg, manual_setpoint->time_boot_ms, manual_setpoint->roll, manual_setpoint->pitch, manual_setpoint->yaw, manual_setpoint->thrust, manual_setpoint->mode_switch, manual_setpoint->manual_override_switch); -} - -/** - * @brief Encode a manual_setpoint struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param manual_setpoint C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_manual_setpoint_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_manual_setpoint_t* manual_setpoint) -{ - return mavlink_msg_manual_setpoint_pack_chan(system_id, component_id, chan, msg, manual_setpoint->time_boot_ms, manual_setpoint->roll, manual_setpoint->pitch, manual_setpoint->yaw, manual_setpoint->thrust, manual_setpoint->mode_switch, manual_setpoint->manual_override_switch); -} - -/** - * @brief Send a manual_setpoint message - * @param chan MAVLink channel to send the message - * - * @param time_boot_ms [ms] Timestamp (time since system boot). - * @param roll [rad/s] Desired roll rate - * @param pitch [rad/s] Desired pitch rate - * @param yaw [rad/s] Desired yaw rate - * @param thrust Collective thrust, normalized to 0 .. 1 - * @param mode_switch Flight mode switch position, 0.. 255 - * @param manual_override_switch Override mode switch position, 0.. 255 - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_manual_setpoint_send(mavlink_channel_t chan, uint32_t time_boot_ms, float roll, float pitch, float yaw, float thrust, uint8_t mode_switch, uint8_t manual_override_switch) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, roll); - _mav_put_float(buf, 8, pitch); - _mav_put_float(buf, 12, yaw); - _mav_put_float(buf, 16, thrust); - _mav_put_uint8_t(buf, 20, mode_switch); - _mav_put_uint8_t(buf, 21, manual_override_switch); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MANUAL_SETPOINT, buf, MAVLINK_MSG_ID_MANUAL_SETPOINT_MIN_LEN, MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN, MAVLINK_MSG_ID_MANUAL_SETPOINT_CRC); -#else - mavlink_manual_setpoint_t packet; - packet.time_boot_ms = time_boot_ms; - packet.roll = roll; - packet.pitch = pitch; - packet.yaw = yaw; - packet.thrust = thrust; - packet.mode_switch = mode_switch; - packet.manual_override_switch = manual_override_switch; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MANUAL_SETPOINT, (const char *)&packet, MAVLINK_MSG_ID_MANUAL_SETPOINT_MIN_LEN, MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN, MAVLINK_MSG_ID_MANUAL_SETPOINT_CRC); -#endif -} - -/** - * @brief Send a manual_setpoint message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_manual_setpoint_send_struct(mavlink_channel_t chan, const mavlink_manual_setpoint_t* manual_setpoint) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_manual_setpoint_send(chan, manual_setpoint->time_boot_ms, manual_setpoint->roll, manual_setpoint->pitch, manual_setpoint->yaw, manual_setpoint->thrust, manual_setpoint->mode_switch, manual_setpoint->manual_override_switch); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MANUAL_SETPOINT, (const char *)manual_setpoint, MAVLINK_MSG_ID_MANUAL_SETPOINT_MIN_LEN, MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN, MAVLINK_MSG_ID_MANUAL_SETPOINT_CRC); -#endif -} - -#if MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_manual_setpoint_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, float roll, float pitch, float yaw, float thrust, uint8_t mode_switch, uint8_t manual_override_switch) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, roll); - _mav_put_float(buf, 8, pitch); - _mav_put_float(buf, 12, yaw); - _mav_put_float(buf, 16, thrust); - _mav_put_uint8_t(buf, 20, mode_switch); - _mav_put_uint8_t(buf, 21, manual_override_switch); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MANUAL_SETPOINT, buf, MAVLINK_MSG_ID_MANUAL_SETPOINT_MIN_LEN, MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN, MAVLINK_MSG_ID_MANUAL_SETPOINT_CRC); -#else - mavlink_manual_setpoint_t *packet = (mavlink_manual_setpoint_t *)msgbuf; - packet->time_boot_ms = time_boot_ms; - packet->roll = roll; - packet->pitch = pitch; - packet->yaw = yaw; - packet->thrust = thrust; - packet->mode_switch = mode_switch; - packet->manual_override_switch = manual_override_switch; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MANUAL_SETPOINT, (const char *)packet, MAVLINK_MSG_ID_MANUAL_SETPOINT_MIN_LEN, MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN, MAVLINK_MSG_ID_MANUAL_SETPOINT_CRC); -#endif -} -#endif - -#endif - -// MESSAGE MANUAL_SETPOINT UNPACKING - - -/** - * @brief Get field time_boot_ms from manual_setpoint message - * - * @return [ms] Timestamp (time since system boot). - */ -static inline uint32_t mavlink_msg_manual_setpoint_get_time_boot_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field roll from manual_setpoint message - * - * @return [rad/s] Desired roll rate - */ -static inline float mavlink_msg_manual_setpoint_get_roll(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 4); -} - -/** - * @brief Get field pitch from manual_setpoint message - * - * @return [rad/s] Desired pitch rate - */ -static inline float mavlink_msg_manual_setpoint_get_pitch(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field yaw from manual_setpoint message - * - * @return [rad/s] Desired yaw rate - */ -static inline float mavlink_msg_manual_setpoint_get_yaw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field thrust from manual_setpoint message - * - * @return Collective thrust, normalized to 0 .. 1 - */ -static inline float mavlink_msg_manual_setpoint_get_thrust(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field mode_switch from manual_setpoint message - * - * @return Flight mode switch position, 0.. 255 - */ -static inline uint8_t mavlink_msg_manual_setpoint_get_mode_switch(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 20); -} - -/** - * @brief Get field manual_override_switch from manual_setpoint message - * - * @return Override mode switch position, 0.. 255 - */ -static inline uint8_t mavlink_msg_manual_setpoint_get_manual_override_switch(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 21); -} - -/** - * @brief Decode a manual_setpoint message into a struct - * - * @param msg The message to decode - * @param manual_setpoint C-struct to decode the message contents into - */ -static inline void mavlink_msg_manual_setpoint_decode(const mavlink_message_t* msg, mavlink_manual_setpoint_t* manual_setpoint) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - manual_setpoint->time_boot_ms = mavlink_msg_manual_setpoint_get_time_boot_ms(msg); - manual_setpoint->roll = mavlink_msg_manual_setpoint_get_roll(msg); - manual_setpoint->pitch = mavlink_msg_manual_setpoint_get_pitch(msg); - manual_setpoint->yaw = mavlink_msg_manual_setpoint_get_yaw(msg); - manual_setpoint->thrust = mavlink_msg_manual_setpoint_get_thrust(msg); - manual_setpoint->mode_switch = mavlink_msg_manual_setpoint_get_mode_switch(msg); - manual_setpoint->manual_override_switch = mavlink_msg_manual_setpoint_get_manual_override_switch(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN? msg->len : MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN; - memset(manual_setpoint, 0, MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN); - memcpy(manual_setpoint, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_memory_vect.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_memory_vect.h deleted file mode 100644 index 61a73862..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_memory_vect.h +++ /dev/null @@ -1,280 +0,0 @@ -#pragma once -// MESSAGE MEMORY_VECT PACKING - -#define MAVLINK_MSG_ID_MEMORY_VECT 249 - - -typedef struct __mavlink_memory_vect_t { - uint16_t address; /*< Starting address of the debug variables*/ - uint8_t ver; /*< Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below*/ - uint8_t type; /*< Type code of the memory variables. for ver = 1: 0=16 x int16_t, 1=16 x uint16_t, 2=16 x Q15, 3=16 x 1Q14*/ - int8_t value[32]; /*< Memory contents at specified address*/ -} mavlink_memory_vect_t; - -#define MAVLINK_MSG_ID_MEMORY_VECT_LEN 36 -#define MAVLINK_MSG_ID_MEMORY_VECT_MIN_LEN 36 -#define MAVLINK_MSG_ID_249_LEN 36 -#define MAVLINK_MSG_ID_249_MIN_LEN 36 - -#define MAVLINK_MSG_ID_MEMORY_VECT_CRC 204 -#define MAVLINK_MSG_ID_249_CRC 204 - -#define MAVLINK_MSG_MEMORY_VECT_FIELD_VALUE_LEN 32 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_MEMORY_VECT { \ - 249, \ - "MEMORY_VECT", \ - 4, \ - { { "address", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_memory_vect_t, address) }, \ - { "ver", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_memory_vect_t, ver) }, \ - { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_memory_vect_t, type) }, \ - { "value", NULL, MAVLINK_TYPE_INT8_T, 32, 4, offsetof(mavlink_memory_vect_t, value) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_MEMORY_VECT { \ - "MEMORY_VECT", \ - 4, \ - { { "address", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_memory_vect_t, address) }, \ - { "ver", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_memory_vect_t, ver) }, \ - { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_memory_vect_t, type) }, \ - { "value", NULL, MAVLINK_TYPE_INT8_T, 32, 4, offsetof(mavlink_memory_vect_t, value) }, \ - } \ -} -#endif - -/** - * @brief Pack a memory_vect message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param address Starting address of the debug variables - * @param ver Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below - * @param type Type code of the memory variables. for ver = 1: 0=16 x int16_t, 1=16 x uint16_t, 2=16 x Q15, 3=16 x 1Q14 - * @param value Memory contents at specified address - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_memory_vect_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint16_t address, uint8_t ver, uint8_t type, const int8_t *value) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MEMORY_VECT_LEN]; - _mav_put_uint16_t(buf, 0, address); - _mav_put_uint8_t(buf, 2, ver); - _mav_put_uint8_t(buf, 3, type); - _mav_put_int8_t_array(buf, 4, value, 32); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MEMORY_VECT_LEN); -#else - mavlink_memory_vect_t packet; - packet.address = address; - packet.ver = ver; - packet.type = type; - mav_array_memcpy(packet.value, value, sizeof(int8_t)*32); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MEMORY_VECT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_MEMORY_VECT; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MEMORY_VECT_MIN_LEN, MAVLINK_MSG_ID_MEMORY_VECT_LEN, MAVLINK_MSG_ID_MEMORY_VECT_CRC); -} - -/** - * @brief Pack a memory_vect message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param address Starting address of the debug variables - * @param ver Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below - * @param type Type code of the memory variables. for ver = 1: 0=16 x int16_t, 1=16 x uint16_t, 2=16 x Q15, 3=16 x 1Q14 - * @param value Memory contents at specified address - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_memory_vect_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint16_t address,uint8_t ver,uint8_t type,const int8_t *value) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MEMORY_VECT_LEN]; - _mav_put_uint16_t(buf, 0, address); - _mav_put_uint8_t(buf, 2, ver); - _mav_put_uint8_t(buf, 3, type); - _mav_put_int8_t_array(buf, 4, value, 32); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MEMORY_VECT_LEN); -#else - mavlink_memory_vect_t packet; - packet.address = address; - packet.ver = ver; - packet.type = type; - mav_array_memcpy(packet.value, value, sizeof(int8_t)*32); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MEMORY_VECT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_MEMORY_VECT; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MEMORY_VECT_MIN_LEN, MAVLINK_MSG_ID_MEMORY_VECT_LEN, MAVLINK_MSG_ID_MEMORY_VECT_CRC); -} - -/** - * @brief Encode a memory_vect struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param memory_vect C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_memory_vect_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_memory_vect_t* memory_vect) -{ - return mavlink_msg_memory_vect_pack(system_id, component_id, msg, memory_vect->address, memory_vect->ver, memory_vect->type, memory_vect->value); -} - -/** - * @brief Encode a memory_vect struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param memory_vect C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_memory_vect_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_memory_vect_t* memory_vect) -{ - return mavlink_msg_memory_vect_pack_chan(system_id, component_id, chan, msg, memory_vect->address, memory_vect->ver, memory_vect->type, memory_vect->value); -} - -/** - * @brief Send a memory_vect message - * @param chan MAVLink channel to send the message - * - * @param address Starting address of the debug variables - * @param ver Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below - * @param type Type code of the memory variables. for ver = 1: 0=16 x int16_t, 1=16 x uint16_t, 2=16 x Q15, 3=16 x 1Q14 - * @param value Memory contents at specified address - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_memory_vect_send(mavlink_channel_t chan, uint16_t address, uint8_t ver, uint8_t type, const int8_t *value) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MEMORY_VECT_LEN]; - _mav_put_uint16_t(buf, 0, address); - _mav_put_uint8_t(buf, 2, ver); - _mav_put_uint8_t(buf, 3, type); - _mav_put_int8_t_array(buf, 4, value, 32); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MEMORY_VECT, buf, MAVLINK_MSG_ID_MEMORY_VECT_MIN_LEN, MAVLINK_MSG_ID_MEMORY_VECT_LEN, MAVLINK_MSG_ID_MEMORY_VECT_CRC); -#else - mavlink_memory_vect_t packet; - packet.address = address; - packet.ver = ver; - packet.type = type; - mav_array_memcpy(packet.value, value, sizeof(int8_t)*32); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MEMORY_VECT, (const char *)&packet, MAVLINK_MSG_ID_MEMORY_VECT_MIN_LEN, MAVLINK_MSG_ID_MEMORY_VECT_LEN, MAVLINK_MSG_ID_MEMORY_VECT_CRC); -#endif -} - -/** - * @brief Send a memory_vect message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_memory_vect_send_struct(mavlink_channel_t chan, const mavlink_memory_vect_t* memory_vect) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_memory_vect_send(chan, memory_vect->address, memory_vect->ver, memory_vect->type, memory_vect->value); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MEMORY_VECT, (const char *)memory_vect, MAVLINK_MSG_ID_MEMORY_VECT_MIN_LEN, MAVLINK_MSG_ID_MEMORY_VECT_LEN, MAVLINK_MSG_ID_MEMORY_VECT_CRC); -#endif -} - -#if MAVLINK_MSG_ID_MEMORY_VECT_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_memory_vect_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint16_t address, uint8_t ver, uint8_t type, const int8_t *value) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint16_t(buf, 0, address); - _mav_put_uint8_t(buf, 2, ver); - _mav_put_uint8_t(buf, 3, type); - _mav_put_int8_t_array(buf, 4, value, 32); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MEMORY_VECT, buf, MAVLINK_MSG_ID_MEMORY_VECT_MIN_LEN, MAVLINK_MSG_ID_MEMORY_VECT_LEN, MAVLINK_MSG_ID_MEMORY_VECT_CRC); -#else - mavlink_memory_vect_t *packet = (mavlink_memory_vect_t *)msgbuf; - packet->address = address; - packet->ver = ver; - packet->type = type; - mav_array_memcpy(packet->value, value, sizeof(int8_t)*32); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MEMORY_VECT, (const char *)packet, MAVLINK_MSG_ID_MEMORY_VECT_MIN_LEN, MAVLINK_MSG_ID_MEMORY_VECT_LEN, MAVLINK_MSG_ID_MEMORY_VECT_CRC); -#endif -} -#endif - -#endif - -// MESSAGE MEMORY_VECT UNPACKING - - -/** - * @brief Get field address from memory_vect message - * - * @return Starting address of the debug variables - */ -static inline uint16_t mavlink_msg_memory_vect_get_address(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 0); -} - -/** - * @brief Get field ver from memory_vect message - * - * @return Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below - */ -static inline uint8_t mavlink_msg_memory_vect_get_ver(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 2); -} - -/** - * @brief Get field type from memory_vect message - * - * @return Type code of the memory variables. for ver = 1: 0=16 x int16_t, 1=16 x uint16_t, 2=16 x Q15, 3=16 x 1Q14 - */ -static inline uint8_t mavlink_msg_memory_vect_get_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 3); -} - -/** - * @brief Get field value from memory_vect message - * - * @return Memory contents at specified address - */ -static inline uint16_t mavlink_msg_memory_vect_get_value(const mavlink_message_t* msg, int8_t *value) -{ - return _MAV_RETURN_int8_t_array(msg, value, 32, 4); -} - -/** - * @brief Decode a memory_vect message into a struct - * - * @param msg The message to decode - * @param memory_vect C-struct to decode the message contents into - */ -static inline void mavlink_msg_memory_vect_decode(const mavlink_message_t* msg, mavlink_memory_vect_t* memory_vect) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - memory_vect->address = mavlink_msg_memory_vect_get_address(msg); - memory_vect->ver = mavlink_msg_memory_vect_get_ver(msg); - memory_vect->type = mavlink_msg_memory_vect_get_type(msg); - mavlink_msg_memory_vect_get_value(msg, memory_vect->value); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_MEMORY_VECT_LEN? msg->len : MAVLINK_MSG_ID_MEMORY_VECT_LEN; - memset(memory_vect, 0, MAVLINK_MSG_ID_MEMORY_VECT_LEN); - memcpy(memory_vect, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_message_interval.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_message_interval.h deleted file mode 100644 index 5a94a182..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_message_interval.h +++ /dev/null @@ -1,238 +0,0 @@ -#pragma once -// MESSAGE MESSAGE_INTERVAL PACKING - -#define MAVLINK_MSG_ID_MESSAGE_INTERVAL 244 - - -typedef struct __mavlink_message_interval_t { - int32_t interval_us; /*< [us] The interval between two messages. A value of -1 indicates this stream is disabled, 0 indicates it is not available, > 0 indicates the interval at which it is sent.*/ - uint16_t message_id; /*< The ID of the requested MAVLink message. v1.0 is limited to 254 messages.*/ -} mavlink_message_interval_t; - -#define MAVLINK_MSG_ID_MESSAGE_INTERVAL_LEN 6 -#define MAVLINK_MSG_ID_MESSAGE_INTERVAL_MIN_LEN 6 -#define MAVLINK_MSG_ID_244_LEN 6 -#define MAVLINK_MSG_ID_244_MIN_LEN 6 - -#define MAVLINK_MSG_ID_MESSAGE_INTERVAL_CRC 95 -#define MAVLINK_MSG_ID_244_CRC 95 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_MESSAGE_INTERVAL { \ - 244, \ - "MESSAGE_INTERVAL", \ - 2, \ - { { "message_id", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_message_interval_t, message_id) }, \ - { "interval_us", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_message_interval_t, interval_us) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_MESSAGE_INTERVAL { \ - "MESSAGE_INTERVAL", \ - 2, \ - { { "message_id", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_message_interval_t, message_id) }, \ - { "interval_us", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_message_interval_t, interval_us) }, \ - } \ -} -#endif - -/** - * @brief Pack a message_interval message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param message_id The ID of the requested MAVLink message. v1.0 is limited to 254 messages. - * @param interval_us [us] The interval between two messages. A value of -1 indicates this stream is disabled, 0 indicates it is not available, > 0 indicates the interval at which it is sent. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_message_interval_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint16_t message_id, int32_t interval_us) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MESSAGE_INTERVAL_LEN]; - _mav_put_int32_t(buf, 0, interval_us); - _mav_put_uint16_t(buf, 4, message_id); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MESSAGE_INTERVAL_LEN); -#else - mavlink_message_interval_t packet; - packet.interval_us = interval_us; - packet.message_id = message_id; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MESSAGE_INTERVAL_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_MESSAGE_INTERVAL; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MESSAGE_INTERVAL_MIN_LEN, MAVLINK_MSG_ID_MESSAGE_INTERVAL_LEN, MAVLINK_MSG_ID_MESSAGE_INTERVAL_CRC); -} - -/** - * @brief Pack a message_interval message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param message_id The ID of the requested MAVLink message. v1.0 is limited to 254 messages. - * @param interval_us [us] The interval between two messages. A value of -1 indicates this stream is disabled, 0 indicates it is not available, > 0 indicates the interval at which it is sent. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_message_interval_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint16_t message_id,int32_t interval_us) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MESSAGE_INTERVAL_LEN]; - _mav_put_int32_t(buf, 0, interval_us); - _mav_put_uint16_t(buf, 4, message_id); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MESSAGE_INTERVAL_LEN); -#else - mavlink_message_interval_t packet; - packet.interval_us = interval_us; - packet.message_id = message_id; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MESSAGE_INTERVAL_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_MESSAGE_INTERVAL; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MESSAGE_INTERVAL_MIN_LEN, MAVLINK_MSG_ID_MESSAGE_INTERVAL_LEN, MAVLINK_MSG_ID_MESSAGE_INTERVAL_CRC); -} - -/** - * @brief Encode a message_interval struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param message_interval C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_message_interval_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_message_interval_t* message_interval) -{ - return mavlink_msg_message_interval_pack(system_id, component_id, msg, message_interval->message_id, message_interval->interval_us); -} - -/** - * @brief Encode a message_interval struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param message_interval C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_message_interval_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_message_interval_t* message_interval) -{ - return mavlink_msg_message_interval_pack_chan(system_id, component_id, chan, msg, message_interval->message_id, message_interval->interval_us); -} - -/** - * @brief Send a message_interval message - * @param chan MAVLink channel to send the message - * - * @param message_id The ID of the requested MAVLink message. v1.0 is limited to 254 messages. - * @param interval_us [us] The interval between two messages. A value of -1 indicates this stream is disabled, 0 indicates it is not available, > 0 indicates the interval at which it is sent. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_message_interval_send(mavlink_channel_t chan, uint16_t message_id, int32_t interval_us) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MESSAGE_INTERVAL_LEN]; - _mav_put_int32_t(buf, 0, interval_us); - _mav_put_uint16_t(buf, 4, message_id); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MESSAGE_INTERVAL, buf, MAVLINK_MSG_ID_MESSAGE_INTERVAL_MIN_LEN, MAVLINK_MSG_ID_MESSAGE_INTERVAL_LEN, MAVLINK_MSG_ID_MESSAGE_INTERVAL_CRC); -#else - mavlink_message_interval_t packet; - packet.interval_us = interval_us; - packet.message_id = message_id; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MESSAGE_INTERVAL, (const char *)&packet, MAVLINK_MSG_ID_MESSAGE_INTERVAL_MIN_LEN, MAVLINK_MSG_ID_MESSAGE_INTERVAL_LEN, MAVLINK_MSG_ID_MESSAGE_INTERVAL_CRC); -#endif -} - -/** - * @brief Send a message_interval message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_message_interval_send_struct(mavlink_channel_t chan, const mavlink_message_interval_t* message_interval) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_message_interval_send(chan, message_interval->message_id, message_interval->interval_us); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MESSAGE_INTERVAL, (const char *)message_interval, MAVLINK_MSG_ID_MESSAGE_INTERVAL_MIN_LEN, MAVLINK_MSG_ID_MESSAGE_INTERVAL_LEN, MAVLINK_MSG_ID_MESSAGE_INTERVAL_CRC); -#endif -} - -#if MAVLINK_MSG_ID_MESSAGE_INTERVAL_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_message_interval_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint16_t message_id, int32_t interval_us) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_int32_t(buf, 0, interval_us); - _mav_put_uint16_t(buf, 4, message_id); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MESSAGE_INTERVAL, buf, MAVLINK_MSG_ID_MESSAGE_INTERVAL_MIN_LEN, MAVLINK_MSG_ID_MESSAGE_INTERVAL_LEN, MAVLINK_MSG_ID_MESSAGE_INTERVAL_CRC); -#else - mavlink_message_interval_t *packet = (mavlink_message_interval_t *)msgbuf; - packet->interval_us = interval_us; - packet->message_id = message_id; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MESSAGE_INTERVAL, (const char *)packet, MAVLINK_MSG_ID_MESSAGE_INTERVAL_MIN_LEN, MAVLINK_MSG_ID_MESSAGE_INTERVAL_LEN, MAVLINK_MSG_ID_MESSAGE_INTERVAL_CRC); -#endif -} -#endif - -#endif - -// MESSAGE MESSAGE_INTERVAL UNPACKING - - -/** - * @brief Get field message_id from message_interval message - * - * @return The ID of the requested MAVLink message. v1.0 is limited to 254 messages. - */ -static inline uint16_t mavlink_msg_message_interval_get_message_id(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 4); -} - -/** - * @brief Get field interval_us from message_interval message - * - * @return [us] The interval between two messages. A value of -1 indicates this stream is disabled, 0 indicates it is not available, > 0 indicates the interval at which it is sent. - */ -static inline int32_t mavlink_msg_message_interval_get_interval_us(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 0); -} - -/** - * @brief Decode a message_interval message into a struct - * - * @param msg The message to decode - * @param message_interval C-struct to decode the message contents into - */ -static inline void mavlink_msg_message_interval_decode(const mavlink_message_t* msg, mavlink_message_interval_t* message_interval) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - message_interval->interval_us = mavlink_msg_message_interval_get_interval_us(msg); - message_interval->message_id = mavlink_msg_message_interval_get_message_id(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_MESSAGE_INTERVAL_LEN? msg->len : MAVLINK_MSG_ID_MESSAGE_INTERVAL_LEN; - memset(message_interval, 0, MAVLINK_MSG_ID_MESSAGE_INTERVAL_LEN); - memcpy(message_interval, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_mission_ack.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_mission_ack.h deleted file mode 100644 index 13683c8b..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_mission_ack.h +++ /dev/null @@ -1,288 +0,0 @@ -#pragma once -// MESSAGE MISSION_ACK PACKING - -#define MAVLINK_MSG_ID_MISSION_ACK 47 - - -typedef struct __mavlink_mission_ack_t { - uint8_t target_system; /*< System ID*/ - uint8_t target_component; /*< Component ID*/ - uint8_t type; /*< Mission result.*/ - uint8_t mission_type; /*< Mission type.*/ -} mavlink_mission_ack_t; - -#define MAVLINK_MSG_ID_MISSION_ACK_LEN 4 -#define MAVLINK_MSG_ID_MISSION_ACK_MIN_LEN 3 -#define MAVLINK_MSG_ID_47_LEN 4 -#define MAVLINK_MSG_ID_47_MIN_LEN 3 - -#define MAVLINK_MSG_ID_MISSION_ACK_CRC 153 -#define MAVLINK_MSG_ID_47_CRC 153 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_MISSION_ACK { \ - 47, \ - "MISSION_ACK", \ - 4, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_mission_ack_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_mission_ack_t, target_component) }, \ - { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_mission_ack_t, type) }, \ - { "mission_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_mission_ack_t, mission_type) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_MISSION_ACK { \ - "MISSION_ACK", \ - 4, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_mission_ack_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_mission_ack_t, target_component) }, \ - { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_mission_ack_t, type) }, \ - { "mission_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_mission_ack_t, mission_type) }, \ - } \ -} -#endif - -/** - * @brief Pack a mission_ack message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID - * @param target_component Component ID - * @param type Mission result. - * @param mission_type Mission type. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_mission_ack_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component, uint8_t type, uint8_t mission_type) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MISSION_ACK_LEN]; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - _mav_put_uint8_t(buf, 2, type); - _mav_put_uint8_t(buf, 3, mission_type); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_ACK_LEN); -#else - mavlink_mission_ack_t packet; - packet.target_system = target_system; - packet.target_component = target_component; - packet.type = type; - packet.mission_type = mission_type; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_ACK_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_MISSION_ACK; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_ACK_MIN_LEN, MAVLINK_MSG_ID_MISSION_ACK_LEN, MAVLINK_MSG_ID_MISSION_ACK_CRC); -} - -/** - * @brief Pack a mission_ack message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @param type Mission result. - * @param mission_type Mission type. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_mission_ack_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component,uint8_t type,uint8_t mission_type) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MISSION_ACK_LEN]; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - _mav_put_uint8_t(buf, 2, type); - _mav_put_uint8_t(buf, 3, mission_type); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_ACK_LEN); -#else - mavlink_mission_ack_t packet; - packet.target_system = target_system; - packet.target_component = target_component; - packet.type = type; - packet.mission_type = mission_type; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_ACK_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_MISSION_ACK; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_ACK_MIN_LEN, MAVLINK_MSG_ID_MISSION_ACK_LEN, MAVLINK_MSG_ID_MISSION_ACK_CRC); -} - -/** - * @brief Encode a mission_ack struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param mission_ack C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_mission_ack_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mission_ack_t* mission_ack) -{ - return mavlink_msg_mission_ack_pack(system_id, component_id, msg, mission_ack->target_system, mission_ack->target_component, mission_ack->type, mission_ack->mission_type); -} - -/** - * @brief Encode a mission_ack struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param mission_ack C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_mission_ack_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mission_ack_t* mission_ack) -{ - return mavlink_msg_mission_ack_pack_chan(system_id, component_id, chan, msg, mission_ack->target_system, mission_ack->target_component, mission_ack->type, mission_ack->mission_type); -} - -/** - * @brief Send a mission_ack message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param target_component Component ID - * @param type Mission result. - * @param mission_type Mission type. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_mission_ack_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t type, uint8_t mission_type) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MISSION_ACK_LEN]; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - _mav_put_uint8_t(buf, 2, type); - _mav_put_uint8_t(buf, 3, mission_type); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ACK, buf, MAVLINK_MSG_ID_MISSION_ACK_MIN_LEN, MAVLINK_MSG_ID_MISSION_ACK_LEN, MAVLINK_MSG_ID_MISSION_ACK_CRC); -#else - mavlink_mission_ack_t packet; - packet.target_system = target_system; - packet.target_component = target_component; - packet.type = type; - packet.mission_type = mission_type; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ACK, (const char *)&packet, MAVLINK_MSG_ID_MISSION_ACK_MIN_LEN, MAVLINK_MSG_ID_MISSION_ACK_LEN, MAVLINK_MSG_ID_MISSION_ACK_CRC); -#endif -} - -/** - * @brief Send a mission_ack message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_mission_ack_send_struct(mavlink_channel_t chan, const mavlink_mission_ack_t* mission_ack) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_mission_ack_send(chan, mission_ack->target_system, mission_ack->target_component, mission_ack->type, mission_ack->mission_type); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ACK, (const char *)mission_ack, MAVLINK_MSG_ID_MISSION_ACK_MIN_LEN, MAVLINK_MSG_ID_MISSION_ACK_LEN, MAVLINK_MSG_ID_MISSION_ACK_CRC); -#endif -} - -#if MAVLINK_MSG_ID_MISSION_ACK_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_mission_ack_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t type, uint8_t mission_type) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - _mav_put_uint8_t(buf, 2, type); - _mav_put_uint8_t(buf, 3, mission_type); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ACK, buf, MAVLINK_MSG_ID_MISSION_ACK_MIN_LEN, MAVLINK_MSG_ID_MISSION_ACK_LEN, MAVLINK_MSG_ID_MISSION_ACK_CRC); -#else - mavlink_mission_ack_t *packet = (mavlink_mission_ack_t *)msgbuf; - packet->target_system = target_system; - packet->target_component = target_component; - packet->type = type; - packet->mission_type = mission_type; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ACK, (const char *)packet, MAVLINK_MSG_ID_MISSION_ACK_MIN_LEN, MAVLINK_MSG_ID_MISSION_ACK_LEN, MAVLINK_MSG_ID_MISSION_ACK_CRC); -#endif -} -#endif - -#endif - -// MESSAGE MISSION_ACK UNPACKING - - -/** - * @brief Get field target_system from mission_ack message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_mission_ack_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 0); -} - -/** - * @brief Get field target_component from mission_ack message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_mission_ack_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 1); -} - -/** - * @brief Get field type from mission_ack message - * - * @return Mission result. - */ -static inline uint8_t mavlink_msg_mission_ack_get_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 2); -} - -/** - * @brief Get field mission_type from mission_ack message - * - * @return Mission type. - */ -static inline uint8_t mavlink_msg_mission_ack_get_mission_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 3); -} - -/** - * @brief Decode a mission_ack message into a struct - * - * @param msg The message to decode - * @param mission_ack C-struct to decode the message contents into - */ -static inline void mavlink_msg_mission_ack_decode(const mavlink_message_t* msg, mavlink_mission_ack_t* mission_ack) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mission_ack->target_system = mavlink_msg_mission_ack_get_target_system(msg); - mission_ack->target_component = mavlink_msg_mission_ack_get_target_component(msg); - mission_ack->type = mavlink_msg_mission_ack_get_type(msg); - mission_ack->mission_type = mavlink_msg_mission_ack_get_mission_type(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_MISSION_ACK_LEN? msg->len : MAVLINK_MSG_ID_MISSION_ACK_LEN; - memset(mission_ack, 0, MAVLINK_MSG_ID_MISSION_ACK_LEN); - memcpy(mission_ack, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_mission_clear_all.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_mission_clear_all.h deleted file mode 100644 index 724ea126..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_mission_clear_all.h +++ /dev/null @@ -1,263 +0,0 @@ -#pragma once -// MESSAGE MISSION_CLEAR_ALL PACKING - -#define MAVLINK_MSG_ID_MISSION_CLEAR_ALL 45 - - -typedef struct __mavlink_mission_clear_all_t { - uint8_t target_system; /*< System ID*/ - uint8_t target_component; /*< Component ID*/ - uint8_t mission_type; /*< Mission type.*/ -} mavlink_mission_clear_all_t; - -#define MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN 3 -#define MAVLINK_MSG_ID_MISSION_CLEAR_ALL_MIN_LEN 2 -#define MAVLINK_MSG_ID_45_LEN 3 -#define MAVLINK_MSG_ID_45_MIN_LEN 2 - -#define MAVLINK_MSG_ID_MISSION_CLEAR_ALL_CRC 232 -#define MAVLINK_MSG_ID_45_CRC 232 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_MISSION_CLEAR_ALL { \ - 45, \ - "MISSION_CLEAR_ALL", \ - 3, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_mission_clear_all_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_mission_clear_all_t, target_component) }, \ - { "mission_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_mission_clear_all_t, mission_type) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_MISSION_CLEAR_ALL { \ - "MISSION_CLEAR_ALL", \ - 3, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_mission_clear_all_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_mission_clear_all_t, target_component) }, \ - { "mission_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_mission_clear_all_t, mission_type) }, \ - } \ -} -#endif - -/** - * @brief Pack a mission_clear_all message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID - * @param target_component Component ID - * @param mission_type Mission type. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_mission_clear_all_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component, uint8_t mission_type) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN]; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - _mav_put_uint8_t(buf, 2, mission_type); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN); -#else - mavlink_mission_clear_all_t packet; - packet.target_system = target_system; - packet.target_component = target_component; - packet.mission_type = mission_type; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_MISSION_CLEAR_ALL; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_MIN_LEN, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_CRC); -} - -/** - * @brief Pack a mission_clear_all message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @param mission_type Mission type. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_mission_clear_all_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component,uint8_t mission_type) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN]; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - _mav_put_uint8_t(buf, 2, mission_type); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN); -#else - mavlink_mission_clear_all_t packet; - packet.target_system = target_system; - packet.target_component = target_component; - packet.mission_type = mission_type; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_MISSION_CLEAR_ALL; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_MIN_LEN, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_CRC); -} - -/** - * @brief Encode a mission_clear_all struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param mission_clear_all C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_mission_clear_all_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mission_clear_all_t* mission_clear_all) -{ - return mavlink_msg_mission_clear_all_pack(system_id, component_id, msg, mission_clear_all->target_system, mission_clear_all->target_component, mission_clear_all->mission_type); -} - -/** - * @brief Encode a mission_clear_all struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param mission_clear_all C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_mission_clear_all_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mission_clear_all_t* mission_clear_all) -{ - return mavlink_msg_mission_clear_all_pack_chan(system_id, component_id, chan, msg, mission_clear_all->target_system, mission_clear_all->target_component, mission_clear_all->mission_type); -} - -/** - * @brief Send a mission_clear_all message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param target_component Component ID - * @param mission_type Mission type. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_mission_clear_all_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t mission_type) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN]; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - _mav_put_uint8_t(buf, 2, mission_type); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CLEAR_ALL, buf, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_MIN_LEN, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_CRC); -#else - mavlink_mission_clear_all_t packet; - packet.target_system = target_system; - packet.target_component = target_component; - packet.mission_type = mission_type; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CLEAR_ALL, (const char *)&packet, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_MIN_LEN, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_CRC); -#endif -} - -/** - * @brief Send a mission_clear_all message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_mission_clear_all_send_struct(mavlink_channel_t chan, const mavlink_mission_clear_all_t* mission_clear_all) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_mission_clear_all_send(chan, mission_clear_all->target_system, mission_clear_all->target_component, mission_clear_all->mission_type); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CLEAR_ALL, (const char *)mission_clear_all, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_MIN_LEN, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_CRC); -#endif -} - -#if MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_mission_clear_all_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t mission_type) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - _mav_put_uint8_t(buf, 2, mission_type); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CLEAR_ALL, buf, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_MIN_LEN, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_CRC); -#else - mavlink_mission_clear_all_t *packet = (mavlink_mission_clear_all_t *)msgbuf; - packet->target_system = target_system; - packet->target_component = target_component; - packet->mission_type = mission_type; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CLEAR_ALL, (const char *)packet, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_MIN_LEN, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_CRC); -#endif -} -#endif - -#endif - -// MESSAGE MISSION_CLEAR_ALL UNPACKING - - -/** - * @brief Get field target_system from mission_clear_all message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_mission_clear_all_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 0); -} - -/** - * @brief Get field target_component from mission_clear_all message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_mission_clear_all_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 1); -} - -/** - * @brief Get field mission_type from mission_clear_all message - * - * @return Mission type. - */ -static inline uint8_t mavlink_msg_mission_clear_all_get_mission_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 2); -} - -/** - * @brief Decode a mission_clear_all message into a struct - * - * @param msg The message to decode - * @param mission_clear_all C-struct to decode the message contents into - */ -static inline void mavlink_msg_mission_clear_all_decode(const mavlink_message_t* msg, mavlink_mission_clear_all_t* mission_clear_all) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mission_clear_all->target_system = mavlink_msg_mission_clear_all_get_target_system(msg); - mission_clear_all->target_component = mavlink_msg_mission_clear_all_get_target_component(msg); - mission_clear_all->mission_type = mavlink_msg_mission_clear_all_get_mission_type(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN? msg->len : MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN; - memset(mission_clear_all, 0, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN); - memcpy(mission_clear_all, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_mission_count.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_mission_count.h deleted file mode 100644 index b237e8fd..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_mission_count.h +++ /dev/null @@ -1,288 +0,0 @@ -#pragma once -// MESSAGE MISSION_COUNT PACKING - -#define MAVLINK_MSG_ID_MISSION_COUNT 44 - - -typedef struct __mavlink_mission_count_t { - uint16_t count; /*< Number of mission items in the sequence*/ - uint8_t target_system; /*< System ID*/ - uint8_t target_component; /*< Component ID*/ - uint8_t mission_type; /*< Mission type.*/ -} mavlink_mission_count_t; - -#define MAVLINK_MSG_ID_MISSION_COUNT_LEN 5 -#define MAVLINK_MSG_ID_MISSION_COUNT_MIN_LEN 4 -#define MAVLINK_MSG_ID_44_LEN 5 -#define MAVLINK_MSG_ID_44_MIN_LEN 4 - -#define MAVLINK_MSG_ID_MISSION_COUNT_CRC 221 -#define MAVLINK_MSG_ID_44_CRC 221 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_MISSION_COUNT { \ - 44, \ - "MISSION_COUNT", \ - 4, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_mission_count_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_mission_count_t, target_component) }, \ - { "count", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_mission_count_t, count) }, \ - { "mission_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_mission_count_t, mission_type) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_MISSION_COUNT { \ - "MISSION_COUNT", \ - 4, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_mission_count_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_mission_count_t, target_component) }, \ - { "count", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_mission_count_t, count) }, \ - { "mission_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_mission_count_t, mission_type) }, \ - } \ -} -#endif - -/** - * @brief Pack a mission_count message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID - * @param target_component Component ID - * @param count Number of mission items in the sequence - * @param mission_type Mission type. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_mission_count_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component, uint16_t count, uint8_t mission_type) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MISSION_COUNT_LEN]; - _mav_put_uint16_t(buf, 0, count); - _mav_put_uint8_t(buf, 2, target_system); - _mav_put_uint8_t(buf, 3, target_component); - _mav_put_uint8_t(buf, 4, mission_type); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_COUNT_LEN); -#else - mavlink_mission_count_t packet; - packet.count = count; - packet.target_system = target_system; - packet.target_component = target_component; - packet.mission_type = mission_type; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_COUNT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_MISSION_COUNT; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_COUNT_MIN_LEN, MAVLINK_MSG_ID_MISSION_COUNT_LEN, MAVLINK_MSG_ID_MISSION_COUNT_CRC); -} - -/** - * @brief Pack a mission_count message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @param count Number of mission items in the sequence - * @param mission_type Mission type. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_mission_count_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component,uint16_t count,uint8_t mission_type) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MISSION_COUNT_LEN]; - _mav_put_uint16_t(buf, 0, count); - _mav_put_uint8_t(buf, 2, target_system); - _mav_put_uint8_t(buf, 3, target_component); - _mav_put_uint8_t(buf, 4, mission_type); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_COUNT_LEN); -#else - mavlink_mission_count_t packet; - packet.count = count; - packet.target_system = target_system; - packet.target_component = target_component; - packet.mission_type = mission_type; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_COUNT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_MISSION_COUNT; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_COUNT_MIN_LEN, MAVLINK_MSG_ID_MISSION_COUNT_LEN, MAVLINK_MSG_ID_MISSION_COUNT_CRC); -} - -/** - * @brief Encode a mission_count struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param mission_count C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_mission_count_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mission_count_t* mission_count) -{ - return mavlink_msg_mission_count_pack(system_id, component_id, msg, mission_count->target_system, mission_count->target_component, mission_count->count, mission_count->mission_type); -} - -/** - * @brief Encode a mission_count struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param mission_count C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_mission_count_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mission_count_t* mission_count) -{ - return mavlink_msg_mission_count_pack_chan(system_id, component_id, chan, msg, mission_count->target_system, mission_count->target_component, mission_count->count, mission_count->mission_type); -} - -/** - * @brief Send a mission_count message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param target_component Component ID - * @param count Number of mission items in the sequence - * @param mission_type Mission type. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_mission_count_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t count, uint8_t mission_type) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MISSION_COUNT_LEN]; - _mav_put_uint16_t(buf, 0, count); - _mav_put_uint8_t(buf, 2, target_system); - _mav_put_uint8_t(buf, 3, target_component); - _mav_put_uint8_t(buf, 4, mission_type); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_COUNT, buf, MAVLINK_MSG_ID_MISSION_COUNT_MIN_LEN, MAVLINK_MSG_ID_MISSION_COUNT_LEN, MAVLINK_MSG_ID_MISSION_COUNT_CRC); -#else - mavlink_mission_count_t packet; - packet.count = count; - packet.target_system = target_system; - packet.target_component = target_component; - packet.mission_type = mission_type; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_COUNT, (const char *)&packet, MAVLINK_MSG_ID_MISSION_COUNT_MIN_LEN, MAVLINK_MSG_ID_MISSION_COUNT_LEN, MAVLINK_MSG_ID_MISSION_COUNT_CRC); -#endif -} - -/** - * @brief Send a mission_count message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_mission_count_send_struct(mavlink_channel_t chan, const mavlink_mission_count_t* mission_count) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_mission_count_send(chan, mission_count->target_system, mission_count->target_component, mission_count->count, mission_count->mission_type); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_COUNT, (const char *)mission_count, MAVLINK_MSG_ID_MISSION_COUNT_MIN_LEN, MAVLINK_MSG_ID_MISSION_COUNT_LEN, MAVLINK_MSG_ID_MISSION_COUNT_CRC); -#endif -} - -#if MAVLINK_MSG_ID_MISSION_COUNT_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_mission_count_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t count, uint8_t mission_type) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint16_t(buf, 0, count); - _mav_put_uint8_t(buf, 2, target_system); - _mav_put_uint8_t(buf, 3, target_component); - _mav_put_uint8_t(buf, 4, mission_type); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_COUNT, buf, MAVLINK_MSG_ID_MISSION_COUNT_MIN_LEN, MAVLINK_MSG_ID_MISSION_COUNT_LEN, MAVLINK_MSG_ID_MISSION_COUNT_CRC); -#else - mavlink_mission_count_t *packet = (mavlink_mission_count_t *)msgbuf; - packet->count = count; - packet->target_system = target_system; - packet->target_component = target_component; - packet->mission_type = mission_type; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_COUNT, (const char *)packet, MAVLINK_MSG_ID_MISSION_COUNT_MIN_LEN, MAVLINK_MSG_ID_MISSION_COUNT_LEN, MAVLINK_MSG_ID_MISSION_COUNT_CRC); -#endif -} -#endif - -#endif - -// MESSAGE MISSION_COUNT UNPACKING - - -/** - * @brief Get field target_system from mission_count message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_mission_count_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 2); -} - -/** - * @brief Get field target_component from mission_count message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_mission_count_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 3); -} - -/** - * @brief Get field count from mission_count message - * - * @return Number of mission items in the sequence - */ -static inline uint16_t mavlink_msg_mission_count_get_count(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 0); -} - -/** - * @brief Get field mission_type from mission_count message - * - * @return Mission type. - */ -static inline uint8_t mavlink_msg_mission_count_get_mission_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 4); -} - -/** - * @brief Decode a mission_count message into a struct - * - * @param msg The message to decode - * @param mission_count C-struct to decode the message contents into - */ -static inline void mavlink_msg_mission_count_decode(const mavlink_message_t* msg, mavlink_mission_count_t* mission_count) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mission_count->count = mavlink_msg_mission_count_get_count(msg); - mission_count->target_system = mavlink_msg_mission_count_get_target_system(msg); - mission_count->target_component = mavlink_msg_mission_count_get_target_component(msg); - mission_count->mission_type = mavlink_msg_mission_count_get_mission_type(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_MISSION_COUNT_LEN? msg->len : MAVLINK_MSG_ID_MISSION_COUNT_LEN; - memset(mission_count, 0, MAVLINK_MSG_ID_MISSION_COUNT_LEN); - memcpy(mission_count, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_mission_current.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_mission_current.h deleted file mode 100644 index 83460bb7..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_mission_current.h +++ /dev/null @@ -1,288 +0,0 @@ -#pragma once -// MESSAGE MISSION_CURRENT PACKING - -#define MAVLINK_MSG_ID_MISSION_CURRENT 42 - - -typedef struct __mavlink_mission_current_t { - uint16_t seq; /*< Sequence*/ - uint16_t total; /*< Total number of mission items on vehicle (on last item, sequence == total). If the autopilot stores its home location as part of the mission this will be excluded from the total. 0: Not supported, UINT16_MAX if no mission is present on the vehicle.*/ - uint8_t mission_state; /*< Mission state machine state. MISSION_STATE_UNKNOWN if state reporting not supported.*/ - uint8_t mission_mode; /*< Vehicle is in a mode that can execute mission items or suspended. 0: Unknown, 1: In mission mode, 2: Suspended (not in mission mode).*/ -} mavlink_mission_current_t; - -#define MAVLINK_MSG_ID_MISSION_CURRENT_LEN 6 -#define MAVLINK_MSG_ID_MISSION_CURRENT_MIN_LEN 2 -#define MAVLINK_MSG_ID_42_LEN 6 -#define MAVLINK_MSG_ID_42_MIN_LEN 2 - -#define MAVLINK_MSG_ID_MISSION_CURRENT_CRC 28 -#define MAVLINK_MSG_ID_42_CRC 28 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_MISSION_CURRENT { \ - 42, \ - "MISSION_CURRENT", \ - 4, \ - { { "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_mission_current_t, seq) }, \ - { "total", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_mission_current_t, total) }, \ - { "mission_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_mission_current_t, mission_state) }, \ - { "mission_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_mission_current_t, mission_mode) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_MISSION_CURRENT { \ - "MISSION_CURRENT", \ - 4, \ - { { "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_mission_current_t, seq) }, \ - { "total", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_mission_current_t, total) }, \ - { "mission_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_mission_current_t, mission_state) }, \ - { "mission_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_mission_current_t, mission_mode) }, \ - } \ -} -#endif - -/** - * @brief Pack a mission_current message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param seq Sequence - * @param total Total number of mission items on vehicle (on last item, sequence == total). If the autopilot stores its home location as part of the mission this will be excluded from the total. 0: Not supported, UINT16_MAX if no mission is present on the vehicle. - * @param mission_state Mission state machine state. MISSION_STATE_UNKNOWN if state reporting not supported. - * @param mission_mode Vehicle is in a mode that can execute mission items or suspended. 0: Unknown, 1: In mission mode, 2: Suspended (not in mission mode). - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_mission_current_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint16_t seq, uint16_t total, uint8_t mission_state, uint8_t mission_mode) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MISSION_CURRENT_LEN]; - _mav_put_uint16_t(buf, 0, seq); - _mav_put_uint16_t(buf, 2, total); - _mav_put_uint8_t(buf, 4, mission_state); - _mav_put_uint8_t(buf, 5, mission_mode); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_CURRENT_LEN); -#else - mavlink_mission_current_t packet; - packet.seq = seq; - packet.total = total; - packet.mission_state = mission_state; - packet.mission_mode = mission_mode; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_CURRENT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_MISSION_CURRENT; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_CURRENT_MIN_LEN, MAVLINK_MSG_ID_MISSION_CURRENT_LEN, MAVLINK_MSG_ID_MISSION_CURRENT_CRC); -} - -/** - * @brief Pack a mission_current message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param seq Sequence - * @param total Total number of mission items on vehicle (on last item, sequence == total). If the autopilot stores its home location as part of the mission this will be excluded from the total. 0: Not supported, UINT16_MAX if no mission is present on the vehicle. - * @param mission_state Mission state machine state. MISSION_STATE_UNKNOWN if state reporting not supported. - * @param mission_mode Vehicle is in a mode that can execute mission items or suspended. 0: Unknown, 1: In mission mode, 2: Suspended (not in mission mode). - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_mission_current_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint16_t seq,uint16_t total,uint8_t mission_state,uint8_t mission_mode) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MISSION_CURRENT_LEN]; - _mav_put_uint16_t(buf, 0, seq); - _mav_put_uint16_t(buf, 2, total); - _mav_put_uint8_t(buf, 4, mission_state); - _mav_put_uint8_t(buf, 5, mission_mode); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_CURRENT_LEN); -#else - mavlink_mission_current_t packet; - packet.seq = seq; - packet.total = total; - packet.mission_state = mission_state; - packet.mission_mode = mission_mode; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_CURRENT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_MISSION_CURRENT; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_CURRENT_MIN_LEN, MAVLINK_MSG_ID_MISSION_CURRENT_LEN, MAVLINK_MSG_ID_MISSION_CURRENT_CRC); -} - -/** - * @brief Encode a mission_current struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param mission_current C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_mission_current_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mission_current_t* mission_current) -{ - return mavlink_msg_mission_current_pack(system_id, component_id, msg, mission_current->seq, mission_current->total, mission_current->mission_state, mission_current->mission_mode); -} - -/** - * @brief Encode a mission_current struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param mission_current C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_mission_current_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mission_current_t* mission_current) -{ - return mavlink_msg_mission_current_pack_chan(system_id, component_id, chan, msg, mission_current->seq, mission_current->total, mission_current->mission_state, mission_current->mission_mode); -} - -/** - * @brief Send a mission_current message - * @param chan MAVLink channel to send the message - * - * @param seq Sequence - * @param total Total number of mission items on vehicle (on last item, sequence == total). If the autopilot stores its home location as part of the mission this will be excluded from the total. 0: Not supported, UINT16_MAX if no mission is present on the vehicle. - * @param mission_state Mission state machine state. MISSION_STATE_UNKNOWN if state reporting not supported. - * @param mission_mode Vehicle is in a mode that can execute mission items or suspended. 0: Unknown, 1: In mission mode, 2: Suspended (not in mission mode). - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_mission_current_send(mavlink_channel_t chan, uint16_t seq, uint16_t total, uint8_t mission_state, uint8_t mission_mode) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MISSION_CURRENT_LEN]; - _mav_put_uint16_t(buf, 0, seq); - _mav_put_uint16_t(buf, 2, total); - _mav_put_uint8_t(buf, 4, mission_state); - _mav_put_uint8_t(buf, 5, mission_mode); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CURRENT, buf, MAVLINK_MSG_ID_MISSION_CURRENT_MIN_LEN, MAVLINK_MSG_ID_MISSION_CURRENT_LEN, MAVLINK_MSG_ID_MISSION_CURRENT_CRC); -#else - mavlink_mission_current_t packet; - packet.seq = seq; - packet.total = total; - packet.mission_state = mission_state; - packet.mission_mode = mission_mode; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CURRENT, (const char *)&packet, MAVLINK_MSG_ID_MISSION_CURRENT_MIN_LEN, MAVLINK_MSG_ID_MISSION_CURRENT_LEN, MAVLINK_MSG_ID_MISSION_CURRENT_CRC); -#endif -} - -/** - * @brief Send a mission_current message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_mission_current_send_struct(mavlink_channel_t chan, const mavlink_mission_current_t* mission_current) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_mission_current_send(chan, mission_current->seq, mission_current->total, mission_current->mission_state, mission_current->mission_mode); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CURRENT, (const char *)mission_current, MAVLINK_MSG_ID_MISSION_CURRENT_MIN_LEN, MAVLINK_MSG_ID_MISSION_CURRENT_LEN, MAVLINK_MSG_ID_MISSION_CURRENT_CRC); -#endif -} - -#if MAVLINK_MSG_ID_MISSION_CURRENT_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_mission_current_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint16_t seq, uint16_t total, uint8_t mission_state, uint8_t mission_mode) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint16_t(buf, 0, seq); - _mav_put_uint16_t(buf, 2, total); - _mav_put_uint8_t(buf, 4, mission_state); - _mav_put_uint8_t(buf, 5, mission_mode); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CURRENT, buf, MAVLINK_MSG_ID_MISSION_CURRENT_MIN_LEN, MAVLINK_MSG_ID_MISSION_CURRENT_LEN, MAVLINK_MSG_ID_MISSION_CURRENT_CRC); -#else - mavlink_mission_current_t *packet = (mavlink_mission_current_t *)msgbuf; - packet->seq = seq; - packet->total = total; - packet->mission_state = mission_state; - packet->mission_mode = mission_mode; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CURRENT, (const char *)packet, MAVLINK_MSG_ID_MISSION_CURRENT_MIN_LEN, MAVLINK_MSG_ID_MISSION_CURRENT_LEN, MAVLINK_MSG_ID_MISSION_CURRENT_CRC); -#endif -} -#endif - -#endif - -// MESSAGE MISSION_CURRENT UNPACKING - - -/** - * @brief Get field seq from mission_current message - * - * @return Sequence - */ -static inline uint16_t mavlink_msg_mission_current_get_seq(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 0); -} - -/** - * @brief Get field total from mission_current message - * - * @return Total number of mission items on vehicle (on last item, sequence == total). If the autopilot stores its home location as part of the mission this will be excluded from the total. 0: Not supported, UINT16_MAX if no mission is present on the vehicle. - */ -static inline uint16_t mavlink_msg_mission_current_get_total(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 2); -} - -/** - * @brief Get field mission_state from mission_current message - * - * @return Mission state machine state. MISSION_STATE_UNKNOWN if state reporting not supported. - */ -static inline uint8_t mavlink_msg_mission_current_get_mission_state(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 4); -} - -/** - * @brief Get field mission_mode from mission_current message - * - * @return Vehicle is in a mode that can execute mission items or suspended. 0: Unknown, 1: In mission mode, 2: Suspended (not in mission mode). - */ -static inline uint8_t mavlink_msg_mission_current_get_mission_mode(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 5); -} - -/** - * @brief Decode a mission_current message into a struct - * - * @param msg The message to decode - * @param mission_current C-struct to decode the message contents into - */ -static inline void mavlink_msg_mission_current_decode(const mavlink_message_t* msg, mavlink_mission_current_t* mission_current) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mission_current->seq = mavlink_msg_mission_current_get_seq(msg); - mission_current->total = mavlink_msg_mission_current_get_total(msg); - mission_current->mission_state = mavlink_msg_mission_current_get_mission_state(msg); - mission_current->mission_mode = mavlink_msg_mission_current_get_mission_mode(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_MISSION_CURRENT_LEN? msg->len : MAVLINK_MSG_ID_MISSION_CURRENT_LEN; - memset(mission_current, 0, MAVLINK_MSG_ID_MISSION_CURRENT_LEN); - memcpy(mission_current, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_mission_item.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_mission_item.h deleted file mode 100644 index 1394f866..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_mission_item.h +++ /dev/null @@ -1,563 +0,0 @@ -#pragma once -// MESSAGE MISSION_ITEM PACKING - -#define MAVLINK_MSG_ID_MISSION_ITEM 39 - - -typedef struct __mavlink_mission_item_t { - float param1; /*< PARAM1, see MAV_CMD enum*/ - float param2; /*< PARAM2, see MAV_CMD enum*/ - float param3; /*< PARAM3, see MAV_CMD enum*/ - float param4; /*< PARAM4, see MAV_CMD enum*/ - float x; /*< PARAM5 / local: X coordinate, global: latitude*/ - float y; /*< PARAM6 / local: Y coordinate, global: longitude*/ - float z; /*< PARAM7 / local: Z coordinate, global: altitude (relative or absolute, depending on frame).*/ - uint16_t seq; /*< Sequence*/ - uint16_t command; /*< The scheduled action for the waypoint.*/ - uint8_t target_system; /*< System ID*/ - uint8_t target_component; /*< Component ID*/ - uint8_t frame; /*< The coordinate system of the waypoint.*/ - uint8_t current; /*< false:0, true:1*/ - uint8_t autocontinue; /*< Autocontinue to next waypoint. 0: false, 1: true. Set false to pause mission after the item completes.*/ - uint8_t mission_type; /*< Mission type.*/ -} mavlink_mission_item_t; - -#define MAVLINK_MSG_ID_MISSION_ITEM_LEN 38 -#define MAVLINK_MSG_ID_MISSION_ITEM_MIN_LEN 37 -#define MAVLINK_MSG_ID_39_LEN 38 -#define MAVLINK_MSG_ID_39_MIN_LEN 37 - -#define MAVLINK_MSG_ID_MISSION_ITEM_CRC 254 -#define MAVLINK_MSG_ID_39_CRC 254 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_MISSION_ITEM { \ - 39, \ - "MISSION_ITEM", \ - 15, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_mission_item_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_mission_item_t, target_component) }, \ - { "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_mission_item_t, seq) }, \ - { "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_mission_item_t, frame) }, \ - { "command", NULL, MAVLINK_TYPE_UINT16_T, 0, 30, offsetof(mavlink_mission_item_t, command) }, \ - { "current", NULL, MAVLINK_TYPE_UINT8_T, 0, 35, offsetof(mavlink_mission_item_t, current) }, \ - { "autocontinue", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_mission_item_t, autocontinue) }, \ - { "param1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_mission_item_t, param1) }, \ - { "param2", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_mission_item_t, param2) }, \ - { "param3", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_mission_item_t, param3) }, \ - { "param4", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_mission_item_t, param4) }, \ - { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_mission_item_t, x) }, \ - { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_mission_item_t, y) }, \ - { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_mission_item_t, z) }, \ - { "mission_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 37, offsetof(mavlink_mission_item_t, mission_type) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_MISSION_ITEM { \ - "MISSION_ITEM", \ - 15, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_mission_item_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_mission_item_t, target_component) }, \ - { "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_mission_item_t, seq) }, \ - { "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_mission_item_t, frame) }, \ - { "command", NULL, MAVLINK_TYPE_UINT16_T, 0, 30, offsetof(mavlink_mission_item_t, command) }, \ - { "current", NULL, MAVLINK_TYPE_UINT8_T, 0, 35, offsetof(mavlink_mission_item_t, current) }, \ - { "autocontinue", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_mission_item_t, autocontinue) }, \ - { "param1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_mission_item_t, param1) }, \ - { "param2", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_mission_item_t, param2) }, \ - { "param3", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_mission_item_t, param3) }, \ - { "param4", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_mission_item_t, param4) }, \ - { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_mission_item_t, x) }, \ - { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_mission_item_t, y) }, \ - { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_mission_item_t, z) }, \ - { "mission_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 37, offsetof(mavlink_mission_item_t, mission_type) }, \ - } \ -} -#endif - -/** - * @brief Pack a mission_item message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID - * @param target_component Component ID - * @param seq Sequence - * @param frame The coordinate system of the waypoint. - * @param command The scheduled action for the waypoint. - * @param current false:0, true:1 - * @param autocontinue Autocontinue to next waypoint. 0: false, 1: true. Set false to pause mission after the item completes. - * @param param1 PARAM1, see MAV_CMD enum - * @param param2 PARAM2, see MAV_CMD enum - * @param param3 PARAM3, see MAV_CMD enum - * @param param4 PARAM4, see MAV_CMD enum - * @param x PARAM5 / local: X coordinate, global: latitude - * @param y PARAM6 / local: Y coordinate, global: longitude - * @param z PARAM7 / local: Z coordinate, global: altitude (relative or absolute, depending on frame). - * @param mission_type Mission type. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_mission_item_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component, uint16_t seq, uint8_t frame, uint16_t command, uint8_t current, uint8_t autocontinue, float param1, float param2, float param3, float param4, float x, float y, float z, uint8_t mission_type) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MISSION_ITEM_LEN]; - _mav_put_float(buf, 0, param1); - _mav_put_float(buf, 4, param2); - _mav_put_float(buf, 8, param3); - _mav_put_float(buf, 12, param4); - _mav_put_float(buf, 16, x); - _mav_put_float(buf, 20, y); - _mav_put_float(buf, 24, z); - _mav_put_uint16_t(buf, 28, seq); - _mav_put_uint16_t(buf, 30, command); - _mav_put_uint8_t(buf, 32, target_system); - _mav_put_uint8_t(buf, 33, target_component); - _mav_put_uint8_t(buf, 34, frame); - _mav_put_uint8_t(buf, 35, current); - _mav_put_uint8_t(buf, 36, autocontinue); - _mav_put_uint8_t(buf, 37, mission_type); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_ITEM_LEN); -#else - mavlink_mission_item_t packet; - packet.param1 = param1; - packet.param2 = param2; - packet.param3 = param3; - packet.param4 = param4; - packet.x = x; - packet.y = y; - packet.z = z; - packet.seq = seq; - packet.command = command; - packet.target_system = target_system; - packet.target_component = target_component; - packet.frame = frame; - packet.current = current; - packet.autocontinue = autocontinue; - packet.mission_type = mission_type; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_ITEM_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_MISSION_ITEM; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_ITEM_MIN_LEN, MAVLINK_MSG_ID_MISSION_ITEM_LEN, MAVLINK_MSG_ID_MISSION_ITEM_CRC); -} - -/** - * @brief Pack a mission_item message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @param seq Sequence - * @param frame The coordinate system of the waypoint. - * @param command The scheduled action for the waypoint. - * @param current false:0, true:1 - * @param autocontinue Autocontinue to next waypoint. 0: false, 1: true. Set false to pause mission after the item completes. - * @param param1 PARAM1, see MAV_CMD enum - * @param param2 PARAM2, see MAV_CMD enum - * @param param3 PARAM3, see MAV_CMD enum - * @param param4 PARAM4, see MAV_CMD enum - * @param x PARAM5 / local: X coordinate, global: latitude - * @param y PARAM6 / local: Y coordinate, global: longitude - * @param z PARAM7 / local: Z coordinate, global: altitude (relative or absolute, depending on frame). - * @param mission_type Mission type. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_mission_item_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component,uint16_t seq,uint8_t frame,uint16_t command,uint8_t current,uint8_t autocontinue,float param1,float param2,float param3,float param4,float x,float y,float z,uint8_t mission_type) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MISSION_ITEM_LEN]; - _mav_put_float(buf, 0, param1); - _mav_put_float(buf, 4, param2); - _mav_put_float(buf, 8, param3); - _mav_put_float(buf, 12, param4); - _mav_put_float(buf, 16, x); - _mav_put_float(buf, 20, y); - _mav_put_float(buf, 24, z); - _mav_put_uint16_t(buf, 28, seq); - _mav_put_uint16_t(buf, 30, command); - _mav_put_uint8_t(buf, 32, target_system); - _mav_put_uint8_t(buf, 33, target_component); - _mav_put_uint8_t(buf, 34, frame); - _mav_put_uint8_t(buf, 35, current); - _mav_put_uint8_t(buf, 36, autocontinue); - _mav_put_uint8_t(buf, 37, mission_type); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_ITEM_LEN); -#else - mavlink_mission_item_t packet; - packet.param1 = param1; - packet.param2 = param2; - packet.param3 = param3; - packet.param4 = param4; - packet.x = x; - packet.y = y; - packet.z = z; - packet.seq = seq; - packet.command = command; - packet.target_system = target_system; - packet.target_component = target_component; - packet.frame = frame; - packet.current = current; - packet.autocontinue = autocontinue; - packet.mission_type = mission_type; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_ITEM_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_MISSION_ITEM; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_ITEM_MIN_LEN, MAVLINK_MSG_ID_MISSION_ITEM_LEN, MAVLINK_MSG_ID_MISSION_ITEM_CRC); -} - -/** - * @brief Encode a mission_item struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param mission_item C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_mission_item_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mission_item_t* mission_item) -{ - return mavlink_msg_mission_item_pack(system_id, component_id, msg, mission_item->target_system, mission_item->target_component, mission_item->seq, mission_item->frame, mission_item->command, mission_item->current, mission_item->autocontinue, mission_item->param1, mission_item->param2, mission_item->param3, mission_item->param4, mission_item->x, mission_item->y, mission_item->z, mission_item->mission_type); -} - -/** - * @brief Encode a mission_item struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param mission_item C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_mission_item_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mission_item_t* mission_item) -{ - return mavlink_msg_mission_item_pack_chan(system_id, component_id, chan, msg, mission_item->target_system, mission_item->target_component, mission_item->seq, mission_item->frame, mission_item->command, mission_item->current, mission_item->autocontinue, mission_item->param1, mission_item->param2, mission_item->param3, mission_item->param4, mission_item->x, mission_item->y, mission_item->z, mission_item->mission_type); -} - -/** - * @brief Send a mission_item message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param target_component Component ID - * @param seq Sequence - * @param frame The coordinate system of the waypoint. - * @param command The scheduled action for the waypoint. - * @param current false:0, true:1 - * @param autocontinue Autocontinue to next waypoint. 0: false, 1: true. Set false to pause mission after the item completes. - * @param param1 PARAM1, see MAV_CMD enum - * @param param2 PARAM2, see MAV_CMD enum - * @param param3 PARAM3, see MAV_CMD enum - * @param param4 PARAM4, see MAV_CMD enum - * @param x PARAM5 / local: X coordinate, global: latitude - * @param y PARAM6 / local: Y coordinate, global: longitude - * @param z PARAM7 / local: Z coordinate, global: altitude (relative or absolute, depending on frame). - * @param mission_type Mission type. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_mission_item_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t seq, uint8_t frame, uint16_t command, uint8_t current, uint8_t autocontinue, float param1, float param2, float param3, float param4, float x, float y, float z, uint8_t mission_type) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MISSION_ITEM_LEN]; - _mav_put_float(buf, 0, param1); - _mav_put_float(buf, 4, param2); - _mav_put_float(buf, 8, param3); - _mav_put_float(buf, 12, param4); - _mav_put_float(buf, 16, x); - _mav_put_float(buf, 20, y); - _mav_put_float(buf, 24, z); - _mav_put_uint16_t(buf, 28, seq); - _mav_put_uint16_t(buf, 30, command); - _mav_put_uint8_t(buf, 32, target_system); - _mav_put_uint8_t(buf, 33, target_component); - _mav_put_uint8_t(buf, 34, frame); - _mav_put_uint8_t(buf, 35, current); - _mav_put_uint8_t(buf, 36, autocontinue); - _mav_put_uint8_t(buf, 37, mission_type); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM, buf, MAVLINK_MSG_ID_MISSION_ITEM_MIN_LEN, MAVLINK_MSG_ID_MISSION_ITEM_LEN, MAVLINK_MSG_ID_MISSION_ITEM_CRC); -#else - mavlink_mission_item_t packet; - packet.param1 = param1; - packet.param2 = param2; - packet.param3 = param3; - packet.param4 = param4; - packet.x = x; - packet.y = y; - packet.z = z; - packet.seq = seq; - packet.command = command; - packet.target_system = target_system; - packet.target_component = target_component; - packet.frame = frame; - packet.current = current; - packet.autocontinue = autocontinue; - packet.mission_type = mission_type; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM, (const char *)&packet, MAVLINK_MSG_ID_MISSION_ITEM_MIN_LEN, MAVLINK_MSG_ID_MISSION_ITEM_LEN, MAVLINK_MSG_ID_MISSION_ITEM_CRC); -#endif -} - -/** - * @brief Send a mission_item message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_mission_item_send_struct(mavlink_channel_t chan, const mavlink_mission_item_t* mission_item) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_mission_item_send(chan, mission_item->target_system, mission_item->target_component, mission_item->seq, mission_item->frame, mission_item->command, mission_item->current, mission_item->autocontinue, mission_item->param1, mission_item->param2, mission_item->param3, mission_item->param4, mission_item->x, mission_item->y, mission_item->z, mission_item->mission_type); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM, (const char *)mission_item, MAVLINK_MSG_ID_MISSION_ITEM_MIN_LEN, MAVLINK_MSG_ID_MISSION_ITEM_LEN, MAVLINK_MSG_ID_MISSION_ITEM_CRC); -#endif -} - -#if MAVLINK_MSG_ID_MISSION_ITEM_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_mission_item_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t seq, uint8_t frame, uint16_t command, uint8_t current, uint8_t autocontinue, float param1, float param2, float param3, float param4, float x, float y, float z, uint8_t mission_type) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_float(buf, 0, param1); - _mav_put_float(buf, 4, param2); - _mav_put_float(buf, 8, param3); - _mav_put_float(buf, 12, param4); - _mav_put_float(buf, 16, x); - _mav_put_float(buf, 20, y); - _mav_put_float(buf, 24, z); - _mav_put_uint16_t(buf, 28, seq); - _mav_put_uint16_t(buf, 30, command); - _mav_put_uint8_t(buf, 32, target_system); - _mav_put_uint8_t(buf, 33, target_component); - _mav_put_uint8_t(buf, 34, frame); - _mav_put_uint8_t(buf, 35, current); - _mav_put_uint8_t(buf, 36, autocontinue); - _mav_put_uint8_t(buf, 37, mission_type); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM, buf, MAVLINK_MSG_ID_MISSION_ITEM_MIN_LEN, MAVLINK_MSG_ID_MISSION_ITEM_LEN, MAVLINK_MSG_ID_MISSION_ITEM_CRC); -#else - mavlink_mission_item_t *packet = (mavlink_mission_item_t *)msgbuf; - packet->param1 = param1; - packet->param2 = param2; - packet->param3 = param3; - packet->param4 = param4; - packet->x = x; - packet->y = y; - packet->z = z; - packet->seq = seq; - packet->command = command; - packet->target_system = target_system; - packet->target_component = target_component; - packet->frame = frame; - packet->current = current; - packet->autocontinue = autocontinue; - packet->mission_type = mission_type; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM, (const char *)packet, MAVLINK_MSG_ID_MISSION_ITEM_MIN_LEN, MAVLINK_MSG_ID_MISSION_ITEM_LEN, MAVLINK_MSG_ID_MISSION_ITEM_CRC); -#endif -} -#endif - -#endif - -// MESSAGE MISSION_ITEM UNPACKING - - -/** - * @brief Get field target_system from mission_item message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_mission_item_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 32); -} - -/** - * @brief Get field target_component from mission_item message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_mission_item_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 33); -} - -/** - * @brief Get field seq from mission_item message - * - * @return Sequence - */ -static inline uint16_t mavlink_msg_mission_item_get_seq(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 28); -} - -/** - * @brief Get field frame from mission_item message - * - * @return The coordinate system of the waypoint. - */ -static inline uint8_t mavlink_msg_mission_item_get_frame(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 34); -} - -/** - * @brief Get field command from mission_item message - * - * @return The scheduled action for the waypoint. - */ -static inline uint16_t mavlink_msg_mission_item_get_command(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 30); -} - -/** - * @brief Get field current from mission_item message - * - * @return false:0, true:1 - */ -static inline uint8_t mavlink_msg_mission_item_get_current(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 35); -} - -/** - * @brief Get field autocontinue from mission_item message - * - * @return Autocontinue to next waypoint. 0: false, 1: true. Set false to pause mission after the item completes. - */ -static inline uint8_t mavlink_msg_mission_item_get_autocontinue(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 36); -} - -/** - * @brief Get field param1 from mission_item message - * - * @return PARAM1, see MAV_CMD enum - */ -static inline float mavlink_msg_mission_item_get_param1(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 0); -} - -/** - * @brief Get field param2 from mission_item message - * - * @return PARAM2, see MAV_CMD enum - */ -static inline float mavlink_msg_mission_item_get_param2(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 4); -} - -/** - * @brief Get field param3 from mission_item message - * - * @return PARAM3, see MAV_CMD enum - */ -static inline float mavlink_msg_mission_item_get_param3(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field param4 from mission_item message - * - * @return PARAM4, see MAV_CMD enum - */ -static inline float mavlink_msg_mission_item_get_param4(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field x from mission_item message - * - * @return PARAM5 / local: X coordinate, global: latitude - */ -static inline float mavlink_msg_mission_item_get_x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field y from mission_item message - * - * @return PARAM6 / local: Y coordinate, global: longitude - */ -static inline float mavlink_msg_mission_item_get_y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Get field z from mission_item message - * - * @return PARAM7 / local: Z coordinate, global: altitude (relative or absolute, depending on frame). - */ -static inline float mavlink_msg_mission_item_get_z(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Get field mission_type from mission_item message - * - * @return Mission type. - */ -static inline uint8_t mavlink_msg_mission_item_get_mission_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 37); -} - -/** - * @brief Decode a mission_item message into a struct - * - * @param msg The message to decode - * @param mission_item C-struct to decode the message contents into - */ -static inline void mavlink_msg_mission_item_decode(const mavlink_message_t* msg, mavlink_mission_item_t* mission_item) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mission_item->param1 = mavlink_msg_mission_item_get_param1(msg); - mission_item->param2 = mavlink_msg_mission_item_get_param2(msg); - mission_item->param3 = mavlink_msg_mission_item_get_param3(msg); - mission_item->param4 = mavlink_msg_mission_item_get_param4(msg); - mission_item->x = mavlink_msg_mission_item_get_x(msg); - mission_item->y = mavlink_msg_mission_item_get_y(msg); - mission_item->z = mavlink_msg_mission_item_get_z(msg); - mission_item->seq = mavlink_msg_mission_item_get_seq(msg); - mission_item->command = mavlink_msg_mission_item_get_command(msg); - mission_item->target_system = mavlink_msg_mission_item_get_target_system(msg); - mission_item->target_component = mavlink_msg_mission_item_get_target_component(msg); - mission_item->frame = mavlink_msg_mission_item_get_frame(msg); - mission_item->current = mavlink_msg_mission_item_get_current(msg); - mission_item->autocontinue = mavlink_msg_mission_item_get_autocontinue(msg); - mission_item->mission_type = mavlink_msg_mission_item_get_mission_type(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_MISSION_ITEM_LEN? msg->len : MAVLINK_MSG_ID_MISSION_ITEM_LEN; - memset(mission_item, 0, MAVLINK_MSG_ID_MISSION_ITEM_LEN); - memcpy(mission_item, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_mission_item_int.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_mission_item_int.h deleted file mode 100644 index 88e6f5e5..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_mission_item_int.h +++ /dev/null @@ -1,563 +0,0 @@ -#pragma once -// MESSAGE MISSION_ITEM_INT PACKING - -#define MAVLINK_MSG_ID_MISSION_ITEM_INT 73 - - -typedef struct __mavlink_mission_item_int_t { - float param1; /*< PARAM1, see MAV_CMD enum*/ - float param2; /*< PARAM2, see MAV_CMD enum*/ - float param3; /*< PARAM3, see MAV_CMD enum*/ - float param4; /*< PARAM4, see MAV_CMD enum*/ - int32_t x; /*< PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7*/ - int32_t y; /*< PARAM6 / y position: local: x position in meters * 1e4, global: longitude in degrees *10^7*/ - float z; /*< PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame.*/ - uint16_t seq; /*< Waypoint ID (sequence number). Starts at zero. Increases monotonically for each waypoint, no gaps in the sequence (0,1,2,3,4).*/ - uint16_t command; /*< The scheduled action for the waypoint.*/ - uint8_t target_system; /*< System ID*/ - uint8_t target_component; /*< Component ID*/ - uint8_t frame; /*< The coordinate system of the waypoint.*/ - uint8_t current; /*< false:0, true:1*/ - uint8_t autocontinue; /*< Autocontinue to next waypoint. 0: false, 1: true. Set false to pause mission after the item completes.*/ - uint8_t mission_type; /*< Mission type.*/ -} mavlink_mission_item_int_t; - -#define MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN 38 -#define MAVLINK_MSG_ID_MISSION_ITEM_INT_MIN_LEN 37 -#define MAVLINK_MSG_ID_73_LEN 38 -#define MAVLINK_MSG_ID_73_MIN_LEN 37 - -#define MAVLINK_MSG_ID_MISSION_ITEM_INT_CRC 38 -#define MAVLINK_MSG_ID_73_CRC 38 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_MISSION_ITEM_INT { \ - 73, \ - "MISSION_ITEM_INT", \ - 15, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_mission_item_int_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_mission_item_int_t, target_component) }, \ - { "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_mission_item_int_t, seq) }, \ - { "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_mission_item_int_t, frame) }, \ - { "command", NULL, MAVLINK_TYPE_UINT16_T, 0, 30, offsetof(mavlink_mission_item_int_t, command) }, \ - { "current", NULL, MAVLINK_TYPE_UINT8_T, 0, 35, offsetof(mavlink_mission_item_int_t, current) }, \ - { "autocontinue", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_mission_item_int_t, autocontinue) }, \ - { "param1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_mission_item_int_t, param1) }, \ - { "param2", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_mission_item_int_t, param2) }, \ - { "param3", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_mission_item_int_t, param3) }, \ - { "param4", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_mission_item_int_t, param4) }, \ - { "x", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_mission_item_int_t, x) }, \ - { "y", NULL, MAVLINK_TYPE_INT32_T, 0, 20, offsetof(mavlink_mission_item_int_t, y) }, \ - { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_mission_item_int_t, z) }, \ - { "mission_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 37, offsetof(mavlink_mission_item_int_t, mission_type) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_MISSION_ITEM_INT { \ - "MISSION_ITEM_INT", \ - 15, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_mission_item_int_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_mission_item_int_t, target_component) }, \ - { "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_mission_item_int_t, seq) }, \ - { "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_mission_item_int_t, frame) }, \ - { "command", NULL, MAVLINK_TYPE_UINT16_T, 0, 30, offsetof(mavlink_mission_item_int_t, command) }, \ - { "current", NULL, MAVLINK_TYPE_UINT8_T, 0, 35, offsetof(mavlink_mission_item_int_t, current) }, \ - { "autocontinue", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_mission_item_int_t, autocontinue) }, \ - { "param1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_mission_item_int_t, param1) }, \ - { "param2", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_mission_item_int_t, param2) }, \ - { "param3", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_mission_item_int_t, param3) }, \ - { "param4", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_mission_item_int_t, param4) }, \ - { "x", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_mission_item_int_t, x) }, \ - { "y", NULL, MAVLINK_TYPE_INT32_T, 0, 20, offsetof(mavlink_mission_item_int_t, y) }, \ - { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_mission_item_int_t, z) }, \ - { "mission_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 37, offsetof(mavlink_mission_item_int_t, mission_type) }, \ - } \ -} -#endif - -/** - * @brief Pack a mission_item_int message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID - * @param target_component Component ID - * @param seq Waypoint ID (sequence number). Starts at zero. Increases monotonically for each waypoint, no gaps in the sequence (0,1,2,3,4). - * @param frame The coordinate system of the waypoint. - * @param command The scheduled action for the waypoint. - * @param current false:0, true:1 - * @param autocontinue Autocontinue to next waypoint. 0: false, 1: true. Set false to pause mission after the item completes. - * @param param1 PARAM1, see MAV_CMD enum - * @param param2 PARAM2, see MAV_CMD enum - * @param param3 PARAM3, see MAV_CMD enum - * @param param4 PARAM4, see MAV_CMD enum - * @param x PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7 - * @param y PARAM6 / y position: local: x position in meters * 1e4, global: longitude in degrees *10^7 - * @param z PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame. - * @param mission_type Mission type. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_mission_item_int_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component, uint16_t seq, uint8_t frame, uint16_t command, uint8_t current, uint8_t autocontinue, float param1, float param2, float param3, float param4, int32_t x, int32_t y, float z, uint8_t mission_type) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN]; - _mav_put_float(buf, 0, param1); - _mav_put_float(buf, 4, param2); - _mav_put_float(buf, 8, param3); - _mav_put_float(buf, 12, param4); - _mav_put_int32_t(buf, 16, x); - _mav_put_int32_t(buf, 20, y); - _mav_put_float(buf, 24, z); - _mav_put_uint16_t(buf, 28, seq); - _mav_put_uint16_t(buf, 30, command); - _mav_put_uint8_t(buf, 32, target_system); - _mav_put_uint8_t(buf, 33, target_component); - _mav_put_uint8_t(buf, 34, frame); - _mav_put_uint8_t(buf, 35, current); - _mav_put_uint8_t(buf, 36, autocontinue); - _mav_put_uint8_t(buf, 37, mission_type); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN); -#else - mavlink_mission_item_int_t packet; - packet.param1 = param1; - packet.param2 = param2; - packet.param3 = param3; - packet.param4 = param4; - packet.x = x; - packet.y = y; - packet.z = z; - packet.seq = seq; - packet.command = command; - packet.target_system = target_system; - packet.target_component = target_component; - packet.frame = frame; - packet.current = current; - packet.autocontinue = autocontinue; - packet.mission_type = mission_type; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_MISSION_ITEM_INT; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_ITEM_INT_MIN_LEN, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN, MAVLINK_MSG_ID_MISSION_ITEM_INT_CRC); -} - -/** - * @brief Pack a mission_item_int message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @param seq Waypoint ID (sequence number). Starts at zero. Increases monotonically for each waypoint, no gaps in the sequence (0,1,2,3,4). - * @param frame The coordinate system of the waypoint. - * @param command The scheduled action for the waypoint. - * @param current false:0, true:1 - * @param autocontinue Autocontinue to next waypoint. 0: false, 1: true. Set false to pause mission after the item completes. - * @param param1 PARAM1, see MAV_CMD enum - * @param param2 PARAM2, see MAV_CMD enum - * @param param3 PARAM3, see MAV_CMD enum - * @param param4 PARAM4, see MAV_CMD enum - * @param x PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7 - * @param y PARAM6 / y position: local: x position in meters * 1e4, global: longitude in degrees *10^7 - * @param z PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame. - * @param mission_type Mission type. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_mission_item_int_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component,uint16_t seq,uint8_t frame,uint16_t command,uint8_t current,uint8_t autocontinue,float param1,float param2,float param3,float param4,int32_t x,int32_t y,float z,uint8_t mission_type) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN]; - _mav_put_float(buf, 0, param1); - _mav_put_float(buf, 4, param2); - _mav_put_float(buf, 8, param3); - _mav_put_float(buf, 12, param4); - _mav_put_int32_t(buf, 16, x); - _mav_put_int32_t(buf, 20, y); - _mav_put_float(buf, 24, z); - _mav_put_uint16_t(buf, 28, seq); - _mav_put_uint16_t(buf, 30, command); - _mav_put_uint8_t(buf, 32, target_system); - _mav_put_uint8_t(buf, 33, target_component); - _mav_put_uint8_t(buf, 34, frame); - _mav_put_uint8_t(buf, 35, current); - _mav_put_uint8_t(buf, 36, autocontinue); - _mav_put_uint8_t(buf, 37, mission_type); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN); -#else - mavlink_mission_item_int_t packet; - packet.param1 = param1; - packet.param2 = param2; - packet.param3 = param3; - packet.param4 = param4; - packet.x = x; - packet.y = y; - packet.z = z; - packet.seq = seq; - packet.command = command; - packet.target_system = target_system; - packet.target_component = target_component; - packet.frame = frame; - packet.current = current; - packet.autocontinue = autocontinue; - packet.mission_type = mission_type; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_MISSION_ITEM_INT; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_ITEM_INT_MIN_LEN, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN, MAVLINK_MSG_ID_MISSION_ITEM_INT_CRC); -} - -/** - * @brief Encode a mission_item_int struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param mission_item_int C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_mission_item_int_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mission_item_int_t* mission_item_int) -{ - return mavlink_msg_mission_item_int_pack(system_id, component_id, msg, mission_item_int->target_system, mission_item_int->target_component, mission_item_int->seq, mission_item_int->frame, mission_item_int->command, mission_item_int->current, mission_item_int->autocontinue, mission_item_int->param1, mission_item_int->param2, mission_item_int->param3, mission_item_int->param4, mission_item_int->x, mission_item_int->y, mission_item_int->z, mission_item_int->mission_type); -} - -/** - * @brief Encode a mission_item_int struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param mission_item_int C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_mission_item_int_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mission_item_int_t* mission_item_int) -{ - return mavlink_msg_mission_item_int_pack_chan(system_id, component_id, chan, msg, mission_item_int->target_system, mission_item_int->target_component, mission_item_int->seq, mission_item_int->frame, mission_item_int->command, mission_item_int->current, mission_item_int->autocontinue, mission_item_int->param1, mission_item_int->param2, mission_item_int->param3, mission_item_int->param4, mission_item_int->x, mission_item_int->y, mission_item_int->z, mission_item_int->mission_type); -} - -/** - * @brief Send a mission_item_int message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param target_component Component ID - * @param seq Waypoint ID (sequence number). Starts at zero. Increases monotonically for each waypoint, no gaps in the sequence (0,1,2,3,4). - * @param frame The coordinate system of the waypoint. - * @param command The scheduled action for the waypoint. - * @param current false:0, true:1 - * @param autocontinue Autocontinue to next waypoint. 0: false, 1: true. Set false to pause mission after the item completes. - * @param param1 PARAM1, see MAV_CMD enum - * @param param2 PARAM2, see MAV_CMD enum - * @param param3 PARAM3, see MAV_CMD enum - * @param param4 PARAM4, see MAV_CMD enum - * @param x PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7 - * @param y PARAM6 / y position: local: x position in meters * 1e4, global: longitude in degrees *10^7 - * @param z PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame. - * @param mission_type Mission type. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_mission_item_int_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t seq, uint8_t frame, uint16_t command, uint8_t current, uint8_t autocontinue, float param1, float param2, float param3, float param4, int32_t x, int32_t y, float z, uint8_t mission_type) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN]; - _mav_put_float(buf, 0, param1); - _mav_put_float(buf, 4, param2); - _mav_put_float(buf, 8, param3); - _mav_put_float(buf, 12, param4); - _mav_put_int32_t(buf, 16, x); - _mav_put_int32_t(buf, 20, y); - _mav_put_float(buf, 24, z); - _mav_put_uint16_t(buf, 28, seq); - _mav_put_uint16_t(buf, 30, command); - _mav_put_uint8_t(buf, 32, target_system); - _mav_put_uint8_t(buf, 33, target_component); - _mav_put_uint8_t(buf, 34, frame); - _mav_put_uint8_t(buf, 35, current); - _mav_put_uint8_t(buf, 36, autocontinue); - _mav_put_uint8_t(buf, 37, mission_type); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM_INT, buf, MAVLINK_MSG_ID_MISSION_ITEM_INT_MIN_LEN, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN, MAVLINK_MSG_ID_MISSION_ITEM_INT_CRC); -#else - mavlink_mission_item_int_t packet; - packet.param1 = param1; - packet.param2 = param2; - packet.param3 = param3; - packet.param4 = param4; - packet.x = x; - packet.y = y; - packet.z = z; - packet.seq = seq; - packet.command = command; - packet.target_system = target_system; - packet.target_component = target_component; - packet.frame = frame; - packet.current = current; - packet.autocontinue = autocontinue; - packet.mission_type = mission_type; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM_INT, (const char *)&packet, MAVLINK_MSG_ID_MISSION_ITEM_INT_MIN_LEN, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN, MAVLINK_MSG_ID_MISSION_ITEM_INT_CRC); -#endif -} - -/** - * @brief Send a mission_item_int message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_mission_item_int_send_struct(mavlink_channel_t chan, const mavlink_mission_item_int_t* mission_item_int) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_mission_item_int_send(chan, mission_item_int->target_system, mission_item_int->target_component, mission_item_int->seq, mission_item_int->frame, mission_item_int->command, mission_item_int->current, mission_item_int->autocontinue, mission_item_int->param1, mission_item_int->param2, mission_item_int->param3, mission_item_int->param4, mission_item_int->x, mission_item_int->y, mission_item_int->z, mission_item_int->mission_type); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM_INT, (const char *)mission_item_int, MAVLINK_MSG_ID_MISSION_ITEM_INT_MIN_LEN, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN, MAVLINK_MSG_ID_MISSION_ITEM_INT_CRC); -#endif -} - -#if MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_mission_item_int_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t seq, uint8_t frame, uint16_t command, uint8_t current, uint8_t autocontinue, float param1, float param2, float param3, float param4, int32_t x, int32_t y, float z, uint8_t mission_type) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_float(buf, 0, param1); - _mav_put_float(buf, 4, param2); - _mav_put_float(buf, 8, param3); - _mav_put_float(buf, 12, param4); - _mav_put_int32_t(buf, 16, x); - _mav_put_int32_t(buf, 20, y); - _mav_put_float(buf, 24, z); - _mav_put_uint16_t(buf, 28, seq); - _mav_put_uint16_t(buf, 30, command); - _mav_put_uint8_t(buf, 32, target_system); - _mav_put_uint8_t(buf, 33, target_component); - _mav_put_uint8_t(buf, 34, frame); - _mav_put_uint8_t(buf, 35, current); - _mav_put_uint8_t(buf, 36, autocontinue); - _mav_put_uint8_t(buf, 37, mission_type); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM_INT, buf, MAVLINK_MSG_ID_MISSION_ITEM_INT_MIN_LEN, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN, MAVLINK_MSG_ID_MISSION_ITEM_INT_CRC); -#else - mavlink_mission_item_int_t *packet = (mavlink_mission_item_int_t *)msgbuf; - packet->param1 = param1; - packet->param2 = param2; - packet->param3 = param3; - packet->param4 = param4; - packet->x = x; - packet->y = y; - packet->z = z; - packet->seq = seq; - packet->command = command; - packet->target_system = target_system; - packet->target_component = target_component; - packet->frame = frame; - packet->current = current; - packet->autocontinue = autocontinue; - packet->mission_type = mission_type; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM_INT, (const char *)packet, MAVLINK_MSG_ID_MISSION_ITEM_INT_MIN_LEN, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN, MAVLINK_MSG_ID_MISSION_ITEM_INT_CRC); -#endif -} -#endif - -#endif - -// MESSAGE MISSION_ITEM_INT UNPACKING - - -/** - * @brief Get field target_system from mission_item_int message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_mission_item_int_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 32); -} - -/** - * @brief Get field target_component from mission_item_int message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_mission_item_int_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 33); -} - -/** - * @brief Get field seq from mission_item_int message - * - * @return Waypoint ID (sequence number). Starts at zero. Increases monotonically for each waypoint, no gaps in the sequence (0,1,2,3,4). - */ -static inline uint16_t mavlink_msg_mission_item_int_get_seq(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 28); -} - -/** - * @brief Get field frame from mission_item_int message - * - * @return The coordinate system of the waypoint. - */ -static inline uint8_t mavlink_msg_mission_item_int_get_frame(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 34); -} - -/** - * @brief Get field command from mission_item_int message - * - * @return The scheduled action for the waypoint. - */ -static inline uint16_t mavlink_msg_mission_item_int_get_command(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 30); -} - -/** - * @brief Get field current from mission_item_int message - * - * @return false:0, true:1 - */ -static inline uint8_t mavlink_msg_mission_item_int_get_current(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 35); -} - -/** - * @brief Get field autocontinue from mission_item_int message - * - * @return Autocontinue to next waypoint. 0: false, 1: true. Set false to pause mission after the item completes. - */ -static inline uint8_t mavlink_msg_mission_item_int_get_autocontinue(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 36); -} - -/** - * @brief Get field param1 from mission_item_int message - * - * @return PARAM1, see MAV_CMD enum - */ -static inline float mavlink_msg_mission_item_int_get_param1(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 0); -} - -/** - * @brief Get field param2 from mission_item_int message - * - * @return PARAM2, see MAV_CMD enum - */ -static inline float mavlink_msg_mission_item_int_get_param2(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 4); -} - -/** - * @brief Get field param3 from mission_item_int message - * - * @return PARAM3, see MAV_CMD enum - */ -static inline float mavlink_msg_mission_item_int_get_param3(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field param4 from mission_item_int message - * - * @return PARAM4, see MAV_CMD enum - */ -static inline float mavlink_msg_mission_item_int_get_param4(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field x from mission_item_int message - * - * @return PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7 - */ -static inline int32_t mavlink_msg_mission_item_int_get_x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 16); -} - -/** - * @brief Get field y from mission_item_int message - * - * @return PARAM6 / y position: local: x position in meters * 1e4, global: longitude in degrees *10^7 - */ -static inline int32_t mavlink_msg_mission_item_int_get_y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 20); -} - -/** - * @brief Get field z from mission_item_int message - * - * @return PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame. - */ -static inline float mavlink_msg_mission_item_int_get_z(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Get field mission_type from mission_item_int message - * - * @return Mission type. - */ -static inline uint8_t mavlink_msg_mission_item_int_get_mission_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 37); -} - -/** - * @brief Decode a mission_item_int message into a struct - * - * @param msg The message to decode - * @param mission_item_int C-struct to decode the message contents into - */ -static inline void mavlink_msg_mission_item_int_decode(const mavlink_message_t* msg, mavlink_mission_item_int_t* mission_item_int) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mission_item_int->param1 = mavlink_msg_mission_item_int_get_param1(msg); - mission_item_int->param2 = mavlink_msg_mission_item_int_get_param2(msg); - mission_item_int->param3 = mavlink_msg_mission_item_int_get_param3(msg); - mission_item_int->param4 = mavlink_msg_mission_item_int_get_param4(msg); - mission_item_int->x = mavlink_msg_mission_item_int_get_x(msg); - mission_item_int->y = mavlink_msg_mission_item_int_get_y(msg); - mission_item_int->z = mavlink_msg_mission_item_int_get_z(msg); - mission_item_int->seq = mavlink_msg_mission_item_int_get_seq(msg); - mission_item_int->command = mavlink_msg_mission_item_int_get_command(msg); - mission_item_int->target_system = mavlink_msg_mission_item_int_get_target_system(msg); - mission_item_int->target_component = mavlink_msg_mission_item_int_get_target_component(msg); - mission_item_int->frame = mavlink_msg_mission_item_int_get_frame(msg); - mission_item_int->current = mavlink_msg_mission_item_int_get_current(msg); - mission_item_int->autocontinue = mavlink_msg_mission_item_int_get_autocontinue(msg); - mission_item_int->mission_type = mavlink_msg_mission_item_int_get_mission_type(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN? msg->len : MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN; - memset(mission_item_int, 0, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN); - memcpy(mission_item_int, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_mission_item_reached.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_mission_item_reached.h deleted file mode 100644 index fbc195db..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_mission_item_reached.h +++ /dev/null @@ -1,213 +0,0 @@ -#pragma once -// MESSAGE MISSION_ITEM_REACHED PACKING - -#define MAVLINK_MSG_ID_MISSION_ITEM_REACHED 46 - - -typedef struct __mavlink_mission_item_reached_t { - uint16_t seq; /*< Sequence*/ -} mavlink_mission_item_reached_t; - -#define MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN 2 -#define MAVLINK_MSG_ID_MISSION_ITEM_REACHED_MIN_LEN 2 -#define MAVLINK_MSG_ID_46_LEN 2 -#define MAVLINK_MSG_ID_46_MIN_LEN 2 - -#define MAVLINK_MSG_ID_MISSION_ITEM_REACHED_CRC 11 -#define MAVLINK_MSG_ID_46_CRC 11 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_MISSION_ITEM_REACHED { \ - 46, \ - "MISSION_ITEM_REACHED", \ - 1, \ - { { "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_mission_item_reached_t, seq) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_MISSION_ITEM_REACHED { \ - "MISSION_ITEM_REACHED", \ - 1, \ - { { "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_mission_item_reached_t, seq) }, \ - } \ -} -#endif - -/** - * @brief Pack a mission_item_reached message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param seq Sequence - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_mission_item_reached_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint16_t seq) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN]; - _mav_put_uint16_t(buf, 0, seq); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN); -#else - mavlink_mission_item_reached_t packet; - packet.seq = seq; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_MISSION_ITEM_REACHED; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_MIN_LEN, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_CRC); -} - -/** - * @brief Pack a mission_item_reached message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param seq Sequence - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_mission_item_reached_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint16_t seq) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN]; - _mav_put_uint16_t(buf, 0, seq); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN); -#else - mavlink_mission_item_reached_t packet; - packet.seq = seq; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_MISSION_ITEM_REACHED; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_MIN_LEN, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_CRC); -} - -/** - * @brief Encode a mission_item_reached struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param mission_item_reached C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_mission_item_reached_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mission_item_reached_t* mission_item_reached) -{ - return mavlink_msg_mission_item_reached_pack(system_id, component_id, msg, mission_item_reached->seq); -} - -/** - * @brief Encode a mission_item_reached struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param mission_item_reached C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_mission_item_reached_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mission_item_reached_t* mission_item_reached) -{ - return mavlink_msg_mission_item_reached_pack_chan(system_id, component_id, chan, msg, mission_item_reached->seq); -} - -/** - * @brief Send a mission_item_reached message - * @param chan MAVLink channel to send the message - * - * @param seq Sequence - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_mission_item_reached_send(mavlink_channel_t chan, uint16_t seq) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN]; - _mav_put_uint16_t(buf, 0, seq); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM_REACHED, buf, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_MIN_LEN, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_CRC); -#else - mavlink_mission_item_reached_t packet; - packet.seq = seq; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM_REACHED, (const char *)&packet, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_MIN_LEN, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_CRC); -#endif -} - -/** - * @brief Send a mission_item_reached message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_mission_item_reached_send_struct(mavlink_channel_t chan, const mavlink_mission_item_reached_t* mission_item_reached) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_mission_item_reached_send(chan, mission_item_reached->seq); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM_REACHED, (const char *)mission_item_reached, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_MIN_LEN, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_CRC); -#endif -} - -#if MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_mission_item_reached_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint16_t seq) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint16_t(buf, 0, seq); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM_REACHED, buf, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_MIN_LEN, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_CRC); -#else - mavlink_mission_item_reached_t *packet = (mavlink_mission_item_reached_t *)msgbuf; - packet->seq = seq; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM_REACHED, (const char *)packet, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_MIN_LEN, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_CRC); -#endif -} -#endif - -#endif - -// MESSAGE MISSION_ITEM_REACHED UNPACKING - - -/** - * @brief Get field seq from mission_item_reached message - * - * @return Sequence - */ -static inline uint16_t mavlink_msg_mission_item_reached_get_seq(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 0); -} - -/** - * @brief Decode a mission_item_reached message into a struct - * - * @param msg The message to decode - * @param mission_item_reached C-struct to decode the message contents into - */ -static inline void mavlink_msg_mission_item_reached_decode(const mavlink_message_t* msg, mavlink_mission_item_reached_t* mission_item_reached) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mission_item_reached->seq = mavlink_msg_mission_item_reached_get_seq(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN? msg->len : MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN; - memset(mission_item_reached, 0, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN); - memcpy(mission_item_reached, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_mission_request.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_mission_request.h deleted file mode 100644 index a2770a1e..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_mission_request.h +++ /dev/null @@ -1,288 +0,0 @@ -#pragma once -// MESSAGE MISSION_REQUEST PACKING - -#define MAVLINK_MSG_ID_MISSION_REQUEST 40 - - -typedef struct __mavlink_mission_request_t { - uint16_t seq; /*< Sequence*/ - uint8_t target_system; /*< System ID*/ - uint8_t target_component; /*< Component ID*/ - uint8_t mission_type; /*< Mission type.*/ -} mavlink_mission_request_t; - -#define MAVLINK_MSG_ID_MISSION_REQUEST_LEN 5 -#define MAVLINK_MSG_ID_MISSION_REQUEST_MIN_LEN 4 -#define MAVLINK_MSG_ID_40_LEN 5 -#define MAVLINK_MSG_ID_40_MIN_LEN 4 - -#define MAVLINK_MSG_ID_MISSION_REQUEST_CRC 230 -#define MAVLINK_MSG_ID_40_CRC 230 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_MISSION_REQUEST { \ - 40, \ - "MISSION_REQUEST", \ - 4, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_mission_request_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_mission_request_t, target_component) }, \ - { "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_mission_request_t, seq) }, \ - { "mission_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_mission_request_t, mission_type) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_MISSION_REQUEST { \ - "MISSION_REQUEST", \ - 4, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_mission_request_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_mission_request_t, target_component) }, \ - { "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_mission_request_t, seq) }, \ - { "mission_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_mission_request_t, mission_type) }, \ - } \ -} -#endif - -/** - * @brief Pack a mission_request message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID - * @param target_component Component ID - * @param seq Sequence - * @param mission_type Mission type. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_mission_request_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component, uint16_t seq, uint8_t mission_type) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MISSION_REQUEST_LEN]; - _mav_put_uint16_t(buf, 0, seq); - _mav_put_uint8_t(buf, 2, target_system); - _mav_put_uint8_t(buf, 3, target_component); - _mav_put_uint8_t(buf, 4, mission_type); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_REQUEST_LEN); -#else - mavlink_mission_request_t packet; - packet.seq = seq; - packet.target_system = target_system; - packet.target_component = target_component; - packet.mission_type = mission_type; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_REQUEST_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_MISSION_REQUEST; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_REQUEST_MIN_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_CRC); -} - -/** - * @brief Pack a mission_request message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @param seq Sequence - * @param mission_type Mission type. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_mission_request_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component,uint16_t seq,uint8_t mission_type) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MISSION_REQUEST_LEN]; - _mav_put_uint16_t(buf, 0, seq); - _mav_put_uint8_t(buf, 2, target_system); - _mav_put_uint8_t(buf, 3, target_component); - _mav_put_uint8_t(buf, 4, mission_type); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_REQUEST_LEN); -#else - mavlink_mission_request_t packet; - packet.seq = seq; - packet.target_system = target_system; - packet.target_component = target_component; - packet.mission_type = mission_type; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_REQUEST_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_MISSION_REQUEST; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_REQUEST_MIN_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_CRC); -} - -/** - * @brief Encode a mission_request struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param mission_request C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_mission_request_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mission_request_t* mission_request) -{ - return mavlink_msg_mission_request_pack(system_id, component_id, msg, mission_request->target_system, mission_request->target_component, mission_request->seq, mission_request->mission_type); -} - -/** - * @brief Encode a mission_request struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param mission_request C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_mission_request_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mission_request_t* mission_request) -{ - return mavlink_msg_mission_request_pack_chan(system_id, component_id, chan, msg, mission_request->target_system, mission_request->target_component, mission_request->seq, mission_request->mission_type); -} - -/** - * @brief Send a mission_request message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param target_component Component ID - * @param seq Sequence - * @param mission_type Mission type. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_mission_request_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t seq, uint8_t mission_type) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MISSION_REQUEST_LEN]; - _mav_put_uint16_t(buf, 0, seq); - _mav_put_uint8_t(buf, 2, target_system); - _mav_put_uint8_t(buf, 3, target_component); - _mav_put_uint8_t(buf, 4, mission_type); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST, buf, MAVLINK_MSG_ID_MISSION_REQUEST_MIN_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_CRC); -#else - mavlink_mission_request_t packet; - packet.seq = seq; - packet.target_system = target_system; - packet.target_component = target_component; - packet.mission_type = mission_type; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST, (const char *)&packet, MAVLINK_MSG_ID_MISSION_REQUEST_MIN_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_CRC); -#endif -} - -/** - * @brief Send a mission_request message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_mission_request_send_struct(mavlink_channel_t chan, const mavlink_mission_request_t* mission_request) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_mission_request_send(chan, mission_request->target_system, mission_request->target_component, mission_request->seq, mission_request->mission_type); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST, (const char *)mission_request, MAVLINK_MSG_ID_MISSION_REQUEST_MIN_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_CRC); -#endif -} - -#if MAVLINK_MSG_ID_MISSION_REQUEST_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_mission_request_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t seq, uint8_t mission_type) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint16_t(buf, 0, seq); - _mav_put_uint8_t(buf, 2, target_system); - _mav_put_uint8_t(buf, 3, target_component); - _mav_put_uint8_t(buf, 4, mission_type); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST, buf, MAVLINK_MSG_ID_MISSION_REQUEST_MIN_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_CRC); -#else - mavlink_mission_request_t *packet = (mavlink_mission_request_t *)msgbuf; - packet->seq = seq; - packet->target_system = target_system; - packet->target_component = target_component; - packet->mission_type = mission_type; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST, (const char *)packet, MAVLINK_MSG_ID_MISSION_REQUEST_MIN_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_CRC); -#endif -} -#endif - -#endif - -// MESSAGE MISSION_REQUEST UNPACKING - - -/** - * @brief Get field target_system from mission_request message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_mission_request_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 2); -} - -/** - * @brief Get field target_component from mission_request message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_mission_request_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 3); -} - -/** - * @brief Get field seq from mission_request message - * - * @return Sequence - */ -static inline uint16_t mavlink_msg_mission_request_get_seq(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 0); -} - -/** - * @brief Get field mission_type from mission_request message - * - * @return Mission type. - */ -static inline uint8_t mavlink_msg_mission_request_get_mission_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 4); -} - -/** - * @brief Decode a mission_request message into a struct - * - * @param msg The message to decode - * @param mission_request C-struct to decode the message contents into - */ -static inline void mavlink_msg_mission_request_decode(const mavlink_message_t* msg, mavlink_mission_request_t* mission_request) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mission_request->seq = mavlink_msg_mission_request_get_seq(msg); - mission_request->target_system = mavlink_msg_mission_request_get_target_system(msg); - mission_request->target_component = mavlink_msg_mission_request_get_target_component(msg); - mission_request->mission_type = mavlink_msg_mission_request_get_mission_type(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_MISSION_REQUEST_LEN? msg->len : MAVLINK_MSG_ID_MISSION_REQUEST_LEN; - memset(mission_request, 0, MAVLINK_MSG_ID_MISSION_REQUEST_LEN); - memcpy(mission_request, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_mission_request_int.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_mission_request_int.h deleted file mode 100644 index a81e3196..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_mission_request_int.h +++ /dev/null @@ -1,288 +0,0 @@ -#pragma once -// MESSAGE MISSION_REQUEST_INT PACKING - -#define MAVLINK_MSG_ID_MISSION_REQUEST_INT 51 - - -typedef struct __mavlink_mission_request_int_t { - uint16_t seq; /*< Sequence*/ - uint8_t target_system; /*< System ID*/ - uint8_t target_component; /*< Component ID*/ - uint8_t mission_type; /*< Mission type.*/ -} mavlink_mission_request_int_t; - -#define MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN 5 -#define MAVLINK_MSG_ID_MISSION_REQUEST_INT_MIN_LEN 4 -#define MAVLINK_MSG_ID_51_LEN 5 -#define MAVLINK_MSG_ID_51_MIN_LEN 4 - -#define MAVLINK_MSG_ID_MISSION_REQUEST_INT_CRC 196 -#define MAVLINK_MSG_ID_51_CRC 196 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_MISSION_REQUEST_INT { \ - 51, \ - "MISSION_REQUEST_INT", \ - 4, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_mission_request_int_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_mission_request_int_t, target_component) }, \ - { "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_mission_request_int_t, seq) }, \ - { "mission_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_mission_request_int_t, mission_type) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_MISSION_REQUEST_INT { \ - "MISSION_REQUEST_INT", \ - 4, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_mission_request_int_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_mission_request_int_t, target_component) }, \ - { "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_mission_request_int_t, seq) }, \ - { "mission_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_mission_request_int_t, mission_type) }, \ - } \ -} -#endif - -/** - * @brief Pack a mission_request_int message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID - * @param target_component Component ID - * @param seq Sequence - * @param mission_type Mission type. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_mission_request_int_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component, uint16_t seq, uint8_t mission_type) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN]; - _mav_put_uint16_t(buf, 0, seq); - _mav_put_uint8_t(buf, 2, target_system); - _mav_put_uint8_t(buf, 3, target_component); - _mav_put_uint8_t(buf, 4, mission_type); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN); -#else - mavlink_mission_request_int_t packet; - packet.seq = seq; - packet.target_system = target_system; - packet.target_component = target_component; - packet.mission_type = mission_type; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_MISSION_REQUEST_INT; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_REQUEST_INT_MIN_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_INT_CRC); -} - -/** - * @brief Pack a mission_request_int message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @param seq Sequence - * @param mission_type Mission type. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_mission_request_int_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component,uint16_t seq,uint8_t mission_type) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN]; - _mav_put_uint16_t(buf, 0, seq); - _mav_put_uint8_t(buf, 2, target_system); - _mav_put_uint8_t(buf, 3, target_component); - _mav_put_uint8_t(buf, 4, mission_type); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN); -#else - mavlink_mission_request_int_t packet; - packet.seq = seq; - packet.target_system = target_system; - packet.target_component = target_component; - packet.mission_type = mission_type; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_MISSION_REQUEST_INT; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_REQUEST_INT_MIN_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_INT_CRC); -} - -/** - * @brief Encode a mission_request_int struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param mission_request_int C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_mission_request_int_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mission_request_int_t* mission_request_int) -{ - return mavlink_msg_mission_request_int_pack(system_id, component_id, msg, mission_request_int->target_system, mission_request_int->target_component, mission_request_int->seq, mission_request_int->mission_type); -} - -/** - * @brief Encode a mission_request_int struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param mission_request_int C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_mission_request_int_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mission_request_int_t* mission_request_int) -{ - return mavlink_msg_mission_request_int_pack_chan(system_id, component_id, chan, msg, mission_request_int->target_system, mission_request_int->target_component, mission_request_int->seq, mission_request_int->mission_type); -} - -/** - * @brief Send a mission_request_int message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param target_component Component ID - * @param seq Sequence - * @param mission_type Mission type. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_mission_request_int_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t seq, uint8_t mission_type) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN]; - _mav_put_uint16_t(buf, 0, seq); - _mav_put_uint8_t(buf, 2, target_system); - _mav_put_uint8_t(buf, 3, target_component); - _mav_put_uint8_t(buf, 4, mission_type); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_INT, buf, MAVLINK_MSG_ID_MISSION_REQUEST_INT_MIN_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_INT_CRC); -#else - mavlink_mission_request_int_t packet; - packet.seq = seq; - packet.target_system = target_system; - packet.target_component = target_component; - packet.mission_type = mission_type; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_INT, (const char *)&packet, MAVLINK_MSG_ID_MISSION_REQUEST_INT_MIN_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_INT_CRC); -#endif -} - -/** - * @brief Send a mission_request_int message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_mission_request_int_send_struct(mavlink_channel_t chan, const mavlink_mission_request_int_t* mission_request_int) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_mission_request_int_send(chan, mission_request_int->target_system, mission_request_int->target_component, mission_request_int->seq, mission_request_int->mission_type); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_INT, (const char *)mission_request_int, MAVLINK_MSG_ID_MISSION_REQUEST_INT_MIN_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_INT_CRC); -#endif -} - -#if MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_mission_request_int_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t seq, uint8_t mission_type) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint16_t(buf, 0, seq); - _mav_put_uint8_t(buf, 2, target_system); - _mav_put_uint8_t(buf, 3, target_component); - _mav_put_uint8_t(buf, 4, mission_type); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_INT, buf, MAVLINK_MSG_ID_MISSION_REQUEST_INT_MIN_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_INT_CRC); -#else - mavlink_mission_request_int_t *packet = (mavlink_mission_request_int_t *)msgbuf; - packet->seq = seq; - packet->target_system = target_system; - packet->target_component = target_component; - packet->mission_type = mission_type; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_INT, (const char *)packet, MAVLINK_MSG_ID_MISSION_REQUEST_INT_MIN_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_INT_CRC); -#endif -} -#endif - -#endif - -// MESSAGE MISSION_REQUEST_INT UNPACKING - - -/** - * @brief Get field target_system from mission_request_int message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_mission_request_int_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 2); -} - -/** - * @brief Get field target_component from mission_request_int message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_mission_request_int_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 3); -} - -/** - * @brief Get field seq from mission_request_int message - * - * @return Sequence - */ -static inline uint16_t mavlink_msg_mission_request_int_get_seq(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 0); -} - -/** - * @brief Get field mission_type from mission_request_int message - * - * @return Mission type. - */ -static inline uint8_t mavlink_msg_mission_request_int_get_mission_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 4); -} - -/** - * @brief Decode a mission_request_int message into a struct - * - * @param msg The message to decode - * @param mission_request_int C-struct to decode the message contents into - */ -static inline void mavlink_msg_mission_request_int_decode(const mavlink_message_t* msg, mavlink_mission_request_int_t* mission_request_int) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mission_request_int->seq = mavlink_msg_mission_request_int_get_seq(msg); - mission_request_int->target_system = mavlink_msg_mission_request_int_get_target_system(msg); - mission_request_int->target_component = mavlink_msg_mission_request_int_get_target_component(msg); - mission_request_int->mission_type = mavlink_msg_mission_request_int_get_mission_type(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN? msg->len : MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN; - memset(mission_request_int, 0, MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN); - memcpy(mission_request_int, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_mission_request_list.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_mission_request_list.h deleted file mode 100644 index 2e70c224..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_mission_request_list.h +++ /dev/null @@ -1,263 +0,0 @@ -#pragma once -// MESSAGE MISSION_REQUEST_LIST PACKING - -#define MAVLINK_MSG_ID_MISSION_REQUEST_LIST 43 - - -typedef struct __mavlink_mission_request_list_t { - uint8_t target_system; /*< System ID*/ - uint8_t target_component; /*< Component ID*/ - uint8_t mission_type; /*< Mission type.*/ -} mavlink_mission_request_list_t; - -#define MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN 3 -#define MAVLINK_MSG_ID_MISSION_REQUEST_LIST_MIN_LEN 2 -#define MAVLINK_MSG_ID_43_LEN 3 -#define MAVLINK_MSG_ID_43_MIN_LEN 2 - -#define MAVLINK_MSG_ID_MISSION_REQUEST_LIST_CRC 132 -#define MAVLINK_MSG_ID_43_CRC 132 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_MISSION_REQUEST_LIST { \ - 43, \ - "MISSION_REQUEST_LIST", \ - 3, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_mission_request_list_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_mission_request_list_t, target_component) }, \ - { "mission_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_mission_request_list_t, mission_type) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_MISSION_REQUEST_LIST { \ - "MISSION_REQUEST_LIST", \ - 3, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_mission_request_list_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_mission_request_list_t, target_component) }, \ - { "mission_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_mission_request_list_t, mission_type) }, \ - } \ -} -#endif - -/** - * @brief Pack a mission_request_list message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID - * @param target_component Component ID - * @param mission_type Mission type. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_mission_request_list_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component, uint8_t mission_type) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN]; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - _mav_put_uint8_t(buf, 2, mission_type); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN); -#else - mavlink_mission_request_list_t packet; - packet.target_system = target_system; - packet.target_component = target_component; - packet.mission_type = mission_type; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_MISSION_REQUEST_LIST; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_MIN_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_CRC); -} - -/** - * @brief Pack a mission_request_list message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @param mission_type Mission type. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_mission_request_list_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component,uint8_t mission_type) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN]; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - _mav_put_uint8_t(buf, 2, mission_type); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN); -#else - mavlink_mission_request_list_t packet; - packet.target_system = target_system; - packet.target_component = target_component; - packet.mission_type = mission_type; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_MISSION_REQUEST_LIST; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_MIN_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_CRC); -} - -/** - * @brief Encode a mission_request_list struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param mission_request_list C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_mission_request_list_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mission_request_list_t* mission_request_list) -{ - return mavlink_msg_mission_request_list_pack(system_id, component_id, msg, mission_request_list->target_system, mission_request_list->target_component, mission_request_list->mission_type); -} - -/** - * @brief Encode a mission_request_list struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param mission_request_list C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_mission_request_list_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mission_request_list_t* mission_request_list) -{ - return mavlink_msg_mission_request_list_pack_chan(system_id, component_id, chan, msg, mission_request_list->target_system, mission_request_list->target_component, mission_request_list->mission_type); -} - -/** - * @brief Send a mission_request_list message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param target_component Component ID - * @param mission_type Mission type. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_mission_request_list_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t mission_type) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN]; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - _mav_put_uint8_t(buf, 2, mission_type); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_LIST, buf, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_MIN_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_CRC); -#else - mavlink_mission_request_list_t packet; - packet.target_system = target_system; - packet.target_component = target_component; - packet.mission_type = mission_type; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_LIST, (const char *)&packet, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_MIN_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_CRC); -#endif -} - -/** - * @brief Send a mission_request_list message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_mission_request_list_send_struct(mavlink_channel_t chan, const mavlink_mission_request_list_t* mission_request_list) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_mission_request_list_send(chan, mission_request_list->target_system, mission_request_list->target_component, mission_request_list->mission_type); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_LIST, (const char *)mission_request_list, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_MIN_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_CRC); -#endif -} - -#if MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_mission_request_list_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t mission_type) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - _mav_put_uint8_t(buf, 2, mission_type); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_LIST, buf, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_MIN_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_CRC); -#else - mavlink_mission_request_list_t *packet = (mavlink_mission_request_list_t *)msgbuf; - packet->target_system = target_system; - packet->target_component = target_component; - packet->mission_type = mission_type; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_LIST, (const char *)packet, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_MIN_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_CRC); -#endif -} -#endif - -#endif - -// MESSAGE MISSION_REQUEST_LIST UNPACKING - - -/** - * @brief Get field target_system from mission_request_list message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_mission_request_list_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 0); -} - -/** - * @brief Get field target_component from mission_request_list message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_mission_request_list_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 1); -} - -/** - * @brief Get field mission_type from mission_request_list message - * - * @return Mission type. - */ -static inline uint8_t mavlink_msg_mission_request_list_get_mission_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 2); -} - -/** - * @brief Decode a mission_request_list message into a struct - * - * @param msg The message to decode - * @param mission_request_list C-struct to decode the message contents into - */ -static inline void mavlink_msg_mission_request_list_decode(const mavlink_message_t* msg, mavlink_mission_request_list_t* mission_request_list) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mission_request_list->target_system = mavlink_msg_mission_request_list_get_target_system(msg); - mission_request_list->target_component = mavlink_msg_mission_request_list_get_target_component(msg); - mission_request_list->mission_type = mavlink_msg_mission_request_list_get_mission_type(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN? msg->len : MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN; - memset(mission_request_list, 0, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN); - memcpy(mission_request_list, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_mission_request_partial_list.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_mission_request_partial_list.h deleted file mode 100644 index 8612b956..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_mission_request_partial_list.h +++ /dev/null @@ -1,313 +0,0 @@ -#pragma once -// MESSAGE MISSION_REQUEST_PARTIAL_LIST PACKING - -#define MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST 37 - - -typedef struct __mavlink_mission_request_partial_list_t { - int16_t start_index; /*< Start index*/ - int16_t end_index; /*< End index, -1 by default (-1: send list to end). Else a valid index of the list*/ - uint8_t target_system; /*< System ID*/ - uint8_t target_component; /*< Component ID*/ - uint8_t mission_type; /*< Mission type.*/ -} mavlink_mission_request_partial_list_t; - -#define MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN 7 -#define MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_MIN_LEN 6 -#define MAVLINK_MSG_ID_37_LEN 7 -#define MAVLINK_MSG_ID_37_MIN_LEN 6 - -#define MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_CRC 212 -#define MAVLINK_MSG_ID_37_CRC 212 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_MISSION_REQUEST_PARTIAL_LIST { \ - 37, \ - "MISSION_REQUEST_PARTIAL_LIST", \ - 5, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_mission_request_partial_list_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_mission_request_partial_list_t, target_component) }, \ - { "start_index", NULL, MAVLINK_TYPE_INT16_T, 0, 0, offsetof(mavlink_mission_request_partial_list_t, start_index) }, \ - { "end_index", NULL, MAVLINK_TYPE_INT16_T, 0, 2, offsetof(mavlink_mission_request_partial_list_t, end_index) }, \ - { "mission_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_mission_request_partial_list_t, mission_type) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_MISSION_REQUEST_PARTIAL_LIST { \ - "MISSION_REQUEST_PARTIAL_LIST", \ - 5, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_mission_request_partial_list_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_mission_request_partial_list_t, target_component) }, \ - { "start_index", NULL, MAVLINK_TYPE_INT16_T, 0, 0, offsetof(mavlink_mission_request_partial_list_t, start_index) }, \ - { "end_index", NULL, MAVLINK_TYPE_INT16_T, 0, 2, offsetof(mavlink_mission_request_partial_list_t, end_index) }, \ - { "mission_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_mission_request_partial_list_t, mission_type) }, \ - } \ -} -#endif - -/** - * @brief Pack a mission_request_partial_list message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID - * @param target_component Component ID - * @param start_index Start index - * @param end_index End index, -1 by default (-1: send list to end). Else a valid index of the list - * @param mission_type Mission type. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_mission_request_partial_list_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component, int16_t start_index, int16_t end_index, uint8_t mission_type) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN]; - _mav_put_int16_t(buf, 0, start_index); - _mav_put_int16_t(buf, 2, end_index); - _mav_put_uint8_t(buf, 4, target_system); - _mav_put_uint8_t(buf, 5, target_component); - _mav_put_uint8_t(buf, 6, mission_type); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN); -#else - mavlink_mission_request_partial_list_t packet; - packet.start_index = start_index; - packet.end_index = end_index; - packet.target_system = target_system; - packet.target_component = target_component; - packet.mission_type = mission_type; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_MIN_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_CRC); -} - -/** - * @brief Pack a mission_request_partial_list message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @param start_index Start index - * @param end_index End index, -1 by default (-1: send list to end). Else a valid index of the list - * @param mission_type Mission type. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_mission_request_partial_list_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component,int16_t start_index,int16_t end_index,uint8_t mission_type) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN]; - _mav_put_int16_t(buf, 0, start_index); - _mav_put_int16_t(buf, 2, end_index); - _mav_put_uint8_t(buf, 4, target_system); - _mav_put_uint8_t(buf, 5, target_component); - _mav_put_uint8_t(buf, 6, mission_type); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN); -#else - mavlink_mission_request_partial_list_t packet; - packet.start_index = start_index; - packet.end_index = end_index; - packet.target_system = target_system; - packet.target_component = target_component; - packet.mission_type = mission_type; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_MIN_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_CRC); -} - -/** - * @brief Encode a mission_request_partial_list struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param mission_request_partial_list C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_mission_request_partial_list_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mission_request_partial_list_t* mission_request_partial_list) -{ - return mavlink_msg_mission_request_partial_list_pack(system_id, component_id, msg, mission_request_partial_list->target_system, mission_request_partial_list->target_component, mission_request_partial_list->start_index, mission_request_partial_list->end_index, mission_request_partial_list->mission_type); -} - -/** - * @brief Encode a mission_request_partial_list struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param mission_request_partial_list C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_mission_request_partial_list_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mission_request_partial_list_t* mission_request_partial_list) -{ - return mavlink_msg_mission_request_partial_list_pack_chan(system_id, component_id, chan, msg, mission_request_partial_list->target_system, mission_request_partial_list->target_component, mission_request_partial_list->start_index, mission_request_partial_list->end_index, mission_request_partial_list->mission_type); -} - -/** - * @brief Send a mission_request_partial_list message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param target_component Component ID - * @param start_index Start index - * @param end_index End index, -1 by default (-1: send list to end). Else a valid index of the list - * @param mission_type Mission type. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_mission_request_partial_list_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, int16_t start_index, int16_t end_index, uint8_t mission_type) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN]; - _mav_put_int16_t(buf, 0, start_index); - _mav_put_int16_t(buf, 2, end_index); - _mav_put_uint8_t(buf, 4, target_system); - _mav_put_uint8_t(buf, 5, target_component); - _mav_put_uint8_t(buf, 6, mission_type); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST, buf, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_MIN_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_CRC); -#else - mavlink_mission_request_partial_list_t packet; - packet.start_index = start_index; - packet.end_index = end_index; - packet.target_system = target_system; - packet.target_component = target_component; - packet.mission_type = mission_type; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST, (const char *)&packet, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_MIN_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_CRC); -#endif -} - -/** - * @brief Send a mission_request_partial_list message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_mission_request_partial_list_send_struct(mavlink_channel_t chan, const mavlink_mission_request_partial_list_t* mission_request_partial_list) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_mission_request_partial_list_send(chan, mission_request_partial_list->target_system, mission_request_partial_list->target_component, mission_request_partial_list->start_index, mission_request_partial_list->end_index, mission_request_partial_list->mission_type); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST, (const char *)mission_request_partial_list, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_MIN_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_CRC); -#endif -} - -#if MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_mission_request_partial_list_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, int16_t start_index, int16_t end_index, uint8_t mission_type) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_int16_t(buf, 0, start_index); - _mav_put_int16_t(buf, 2, end_index); - _mav_put_uint8_t(buf, 4, target_system); - _mav_put_uint8_t(buf, 5, target_component); - _mav_put_uint8_t(buf, 6, mission_type); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST, buf, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_MIN_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_CRC); -#else - mavlink_mission_request_partial_list_t *packet = (mavlink_mission_request_partial_list_t *)msgbuf; - packet->start_index = start_index; - packet->end_index = end_index; - packet->target_system = target_system; - packet->target_component = target_component; - packet->mission_type = mission_type; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST, (const char *)packet, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_MIN_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_CRC); -#endif -} -#endif - -#endif - -// MESSAGE MISSION_REQUEST_PARTIAL_LIST UNPACKING - - -/** - * @brief Get field target_system from mission_request_partial_list message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_mission_request_partial_list_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 4); -} - -/** - * @brief Get field target_component from mission_request_partial_list message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_mission_request_partial_list_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 5); -} - -/** - * @brief Get field start_index from mission_request_partial_list message - * - * @return Start index - */ -static inline int16_t mavlink_msg_mission_request_partial_list_get_start_index(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 0); -} - -/** - * @brief Get field end_index from mission_request_partial_list message - * - * @return End index, -1 by default (-1: send list to end). Else a valid index of the list - */ -static inline int16_t mavlink_msg_mission_request_partial_list_get_end_index(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 2); -} - -/** - * @brief Get field mission_type from mission_request_partial_list message - * - * @return Mission type. - */ -static inline uint8_t mavlink_msg_mission_request_partial_list_get_mission_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 6); -} - -/** - * @brief Decode a mission_request_partial_list message into a struct - * - * @param msg The message to decode - * @param mission_request_partial_list C-struct to decode the message contents into - */ -static inline void mavlink_msg_mission_request_partial_list_decode(const mavlink_message_t* msg, mavlink_mission_request_partial_list_t* mission_request_partial_list) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mission_request_partial_list->start_index = mavlink_msg_mission_request_partial_list_get_start_index(msg); - mission_request_partial_list->end_index = mavlink_msg_mission_request_partial_list_get_end_index(msg); - mission_request_partial_list->target_system = mavlink_msg_mission_request_partial_list_get_target_system(msg); - mission_request_partial_list->target_component = mavlink_msg_mission_request_partial_list_get_target_component(msg); - mission_request_partial_list->mission_type = mavlink_msg_mission_request_partial_list_get_mission_type(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN? msg->len : MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN; - memset(mission_request_partial_list, 0, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN); - memcpy(mission_request_partial_list, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_mission_set_current.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_mission_set_current.h deleted file mode 100644 index 225fd2d9..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_mission_set_current.h +++ /dev/null @@ -1,263 +0,0 @@ -#pragma once -// MESSAGE MISSION_SET_CURRENT PACKING - -#define MAVLINK_MSG_ID_MISSION_SET_CURRENT 41 - - -typedef struct __mavlink_mission_set_current_t { - uint16_t seq; /*< Sequence*/ - uint8_t target_system; /*< System ID*/ - uint8_t target_component; /*< Component ID*/ -} mavlink_mission_set_current_t; - -#define MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN 4 -#define MAVLINK_MSG_ID_MISSION_SET_CURRENT_MIN_LEN 4 -#define MAVLINK_MSG_ID_41_LEN 4 -#define MAVLINK_MSG_ID_41_MIN_LEN 4 - -#define MAVLINK_MSG_ID_MISSION_SET_CURRENT_CRC 28 -#define MAVLINK_MSG_ID_41_CRC 28 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_MISSION_SET_CURRENT { \ - 41, \ - "MISSION_SET_CURRENT", \ - 3, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_mission_set_current_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_mission_set_current_t, target_component) }, \ - { "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_mission_set_current_t, seq) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_MISSION_SET_CURRENT { \ - "MISSION_SET_CURRENT", \ - 3, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_mission_set_current_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_mission_set_current_t, target_component) }, \ - { "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_mission_set_current_t, seq) }, \ - } \ -} -#endif - -/** - * @brief Pack a mission_set_current message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID - * @param target_component Component ID - * @param seq Sequence - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_mission_set_current_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component, uint16_t seq) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN]; - _mav_put_uint16_t(buf, 0, seq); - _mav_put_uint8_t(buf, 2, target_system); - _mav_put_uint8_t(buf, 3, target_component); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN); -#else - mavlink_mission_set_current_t packet; - packet.seq = seq; - packet.target_system = target_system; - packet.target_component = target_component; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_MISSION_SET_CURRENT; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_SET_CURRENT_MIN_LEN, MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN, MAVLINK_MSG_ID_MISSION_SET_CURRENT_CRC); -} - -/** - * @brief Pack a mission_set_current message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @param seq Sequence - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_mission_set_current_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component,uint16_t seq) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN]; - _mav_put_uint16_t(buf, 0, seq); - _mav_put_uint8_t(buf, 2, target_system); - _mav_put_uint8_t(buf, 3, target_component); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN); -#else - mavlink_mission_set_current_t packet; - packet.seq = seq; - packet.target_system = target_system; - packet.target_component = target_component; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_MISSION_SET_CURRENT; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_SET_CURRENT_MIN_LEN, MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN, MAVLINK_MSG_ID_MISSION_SET_CURRENT_CRC); -} - -/** - * @brief Encode a mission_set_current struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param mission_set_current C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_mission_set_current_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mission_set_current_t* mission_set_current) -{ - return mavlink_msg_mission_set_current_pack(system_id, component_id, msg, mission_set_current->target_system, mission_set_current->target_component, mission_set_current->seq); -} - -/** - * @brief Encode a mission_set_current struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param mission_set_current C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_mission_set_current_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mission_set_current_t* mission_set_current) -{ - return mavlink_msg_mission_set_current_pack_chan(system_id, component_id, chan, msg, mission_set_current->target_system, mission_set_current->target_component, mission_set_current->seq); -} - -/** - * @brief Send a mission_set_current message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param target_component Component ID - * @param seq Sequence - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_mission_set_current_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t seq) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN]; - _mav_put_uint16_t(buf, 0, seq); - _mav_put_uint8_t(buf, 2, target_system); - _mav_put_uint8_t(buf, 3, target_component); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_SET_CURRENT, buf, MAVLINK_MSG_ID_MISSION_SET_CURRENT_MIN_LEN, MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN, MAVLINK_MSG_ID_MISSION_SET_CURRENT_CRC); -#else - mavlink_mission_set_current_t packet; - packet.seq = seq; - packet.target_system = target_system; - packet.target_component = target_component; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_SET_CURRENT, (const char *)&packet, MAVLINK_MSG_ID_MISSION_SET_CURRENT_MIN_LEN, MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN, MAVLINK_MSG_ID_MISSION_SET_CURRENT_CRC); -#endif -} - -/** - * @brief Send a mission_set_current message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_mission_set_current_send_struct(mavlink_channel_t chan, const mavlink_mission_set_current_t* mission_set_current) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_mission_set_current_send(chan, mission_set_current->target_system, mission_set_current->target_component, mission_set_current->seq); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_SET_CURRENT, (const char *)mission_set_current, MAVLINK_MSG_ID_MISSION_SET_CURRENT_MIN_LEN, MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN, MAVLINK_MSG_ID_MISSION_SET_CURRENT_CRC); -#endif -} - -#if MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_mission_set_current_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t seq) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint16_t(buf, 0, seq); - _mav_put_uint8_t(buf, 2, target_system); - _mav_put_uint8_t(buf, 3, target_component); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_SET_CURRENT, buf, MAVLINK_MSG_ID_MISSION_SET_CURRENT_MIN_LEN, MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN, MAVLINK_MSG_ID_MISSION_SET_CURRENT_CRC); -#else - mavlink_mission_set_current_t *packet = (mavlink_mission_set_current_t *)msgbuf; - packet->seq = seq; - packet->target_system = target_system; - packet->target_component = target_component; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_SET_CURRENT, (const char *)packet, MAVLINK_MSG_ID_MISSION_SET_CURRENT_MIN_LEN, MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN, MAVLINK_MSG_ID_MISSION_SET_CURRENT_CRC); -#endif -} -#endif - -#endif - -// MESSAGE MISSION_SET_CURRENT UNPACKING - - -/** - * @brief Get field target_system from mission_set_current message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_mission_set_current_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 2); -} - -/** - * @brief Get field target_component from mission_set_current message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_mission_set_current_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 3); -} - -/** - * @brief Get field seq from mission_set_current message - * - * @return Sequence - */ -static inline uint16_t mavlink_msg_mission_set_current_get_seq(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 0); -} - -/** - * @brief Decode a mission_set_current message into a struct - * - * @param msg The message to decode - * @param mission_set_current C-struct to decode the message contents into - */ -static inline void mavlink_msg_mission_set_current_decode(const mavlink_message_t* msg, mavlink_mission_set_current_t* mission_set_current) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mission_set_current->seq = mavlink_msg_mission_set_current_get_seq(msg); - mission_set_current->target_system = mavlink_msg_mission_set_current_get_target_system(msg); - mission_set_current->target_component = mavlink_msg_mission_set_current_get_target_component(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN? msg->len : MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN; - memset(mission_set_current, 0, MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN); - memcpy(mission_set_current, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_mission_write_partial_list.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_mission_write_partial_list.h deleted file mode 100644 index e6705f60..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_mission_write_partial_list.h +++ /dev/null @@ -1,313 +0,0 @@ -#pragma once -// MESSAGE MISSION_WRITE_PARTIAL_LIST PACKING - -#define MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST 38 - - -typedef struct __mavlink_mission_write_partial_list_t { - int16_t start_index; /*< Start index. Must be smaller / equal to the largest index of the current onboard list.*/ - int16_t end_index; /*< End index, equal or greater than start index.*/ - uint8_t target_system; /*< System ID*/ - uint8_t target_component; /*< Component ID*/ - uint8_t mission_type; /*< Mission type.*/ -} mavlink_mission_write_partial_list_t; - -#define MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN 7 -#define MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_MIN_LEN 6 -#define MAVLINK_MSG_ID_38_LEN 7 -#define MAVLINK_MSG_ID_38_MIN_LEN 6 - -#define MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_CRC 9 -#define MAVLINK_MSG_ID_38_CRC 9 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_MISSION_WRITE_PARTIAL_LIST { \ - 38, \ - "MISSION_WRITE_PARTIAL_LIST", \ - 5, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_mission_write_partial_list_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_mission_write_partial_list_t, target_component) }, \ - { "start_index", NULL, MAVLINK_TYPE_INT16_T, 0, 0, offsetof(mavlink_mission_write_partial_list_t, start_index) }, \ - { "end_index", NULL, MAVLINK_TYPE_INT16_T, 0, 2, offsetof(mavlink_mission_write_partial_list_t, end_index) }, \ - { "mission_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_mission_write_partial_list_t, mission_type) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_MISSION_WRITE_PARTIAL_LIST { \ - "MISSION_WRITE_PARTIAL_LIST", \ - 5, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_mission_write_partial_list_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_mission_write_partial_list_t, target_component) }, \ - { "start_index", NULL, MAVLINK_TYPE_INT16_T, 0, 0, offsetof(mavlink_mission_write_partial_list_t, start_index) }, \ - { "end_index", NULL, MAVLINK_TYPE_INT16_T, 0, 2, offsetof(mavlink_mission_write_partial_list_t, end_index) }, \ - { "mission_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_mission_write_partial_list_t, mission_type) }, \ - } \ -} -#endif - -/** - * @brief Pack a mission_write_partial_list message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID - * @param target_component Component ID - * @param start_index Start index. Must be smaller / equal to the largest index of the current onboard list. - * @param end_index End index, equal or greater than start index. - * @param mission_type Mission type. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_mission_write_partial_list_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component, int16_t start_index, int16_t end_index, uint8_t mission_type) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN]; - _mav_put_int16_t(buf, 0, start_index); - _mav_put_int16_t(buf, 2, end_index); - _mav_put_uint8_t(buf, 4, target_system); - _mav_put_uint8_t(buf, 5, target_component); - _mav_put_uint8_t(buf, 6, mission_type); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN); -#else - mavlink_mission_write_partial_list_t packet; - packet.start_index = start_index; - packet.end_index = end_index; - packet.target_system = target_system; - packet.target_component = target_component; - packet.mission_type = mission_type; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_MIN_LEN, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_CRC); -} - -/** - * @brief Pack a mission_write_partial_list message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @param start_index Start index. Must be smaller / equal to the largest index of the current onboard list. - * @param end_index End index, equal or greater than start index. - * @param mission_type Mission type. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_mission_write_partial_list_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component,int16_t start_index,int16_t end_index,uint8_t mission_type) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN]; - _mav_put_int16_t(buf, 0, start_index); - _mav_put_int16_t(buf, 2, end_index); - _mav_put_uint8_t(buf, 4, target_system); - _mav_put_uint8_t(buf, 5, target_component); - _mav_put_uint8_t(buf, 6, mission_type); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN); -#else - mavlink_mission_write_partial_list_t packet; - packet.start_index = start_index; - packet.end_index = end_index; - packet.target_system = target_system; - packet.target_component = target_component; - packet.mission_type = mission_type; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_MIN_LEN, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_CRC); -} - -/** - * @brief Encode a mission_write_partial_list struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param mission_write_partial_list C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_mission_write_partial_list_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mission_write_partial_list_t* mission_write_partial_list) -{ - return mavlink_msg_mission_write_partial_list_pack(system_id, component_id, msg, mission_write_partial_list->target_system, mission_write_partial_list->target_component, mission_write_partial_list->start_index, mission_write_partial_list->end_index, mission_write_partial_list->mission_type); -} - -/** - * @brief Encode a mission_write_partial_list struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param mission_write_partial_list C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_mission_write_partial_list_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mission_write_partial_list_t* mission_write_partial_list) -{ - return mavlink_msg_mission_write_partial_list_pack_chan(system_id, component_id, chan, msg, mission_write_partial_list->target_system, mission_write_partial_list->target_component, mission_write_partial_list->start_index, mission_write_partial_list->end_index, mission_write_partial_list->mission_type); -} - -/** - * @brief Send a mission_write_partial_list message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param target_component Component ID - * @param start_index Start index. Must be smaller / equal to the largest index of the current onboard list. - * @param end_index End index, equal or greater than start index. - * @param mission_type Mission type. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_mission_write_partial_list_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, int16_t start_index, int16_t end_index, uint8_t mission_type) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN]; - _mav_put_int16_t(buf, 0, start_index); - _mav_put_int16_t(buf, 2, end_index); - _mav_put_uint8_t(buf, 4, target_system); - _mav_put_uint8_t(buf, 5, target_component); - _mav_put_uint8_t(buf, 6, mission_type); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST, buf, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_MIN_LEN, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_CRC); -#else - mavlink_mission_write_partial_list_t packet; - packet.start_index = start_index; - packet.end_index = end_index; - packet.target_system = target_system; - packet.target_component = target_component; - packet.mission_type = mission_type; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST, (const char *)&packet, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_MIN_LEN, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_CRC); -#endif -} - -/** - * @brief Send a mission_write_partial_list message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_mission_write_partial_list_send_struct(mavlink_channel_t chan, const mavlink_mission_write_partial_list_t* mission_write_partial_list) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_mission_write_partial_list_send(chan, mission_write_partial_list->target_system, mission_write_partial_list->target_component, mission_write_partial_list->start_index, mission_write_partial_list->end_index, mission_write_partial_list->mission_type); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST, (const char *)mission_write_partial_list, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_MIN_LEN, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_CRC); -#endif -} - -#if MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_mission_write_partial_list_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, int16_t start_index, int16_t end_index, uint8_t mission_type) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_int16_t(buf, 0, start_index); - _mav_put_int16_t(buf, 2, end_index); - _mav_put_uint8_t(buf, 4, target_system); - _mav_put_uint8_t(buf, 5, target_component); - _mav_put_uint8_t(buf, 6, mission_type); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST, buf, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_MIN_LEN, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_CRC); -#else - mavlink_mission_write_partial_list_t *packet = (mavlink_mission_write_partial_list_t *)msgbuf; - packet->start_index = start_index; - packet->end_index = end_index; - packet->target_system = target_system; - packet->target_component = target_component; - packet->mission_type = mission_type; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST, (const char *)packet, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_MIN_LEN, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_CRC); -#endif -} -#endif - -#endif - -// MESSAGE MISSION_WRITE_PARTIAL_LIST UNPACKING - - -/** - * @brief Get field target_system from mission_write_partial_list message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_mission_write_partial_list_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 4); -} - -/** - * @brief Get field target_component from mission_write_partial_list message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_mission_write_partial_list_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 5); -} - -/** - * @brief Get field start_index from mission_write_partial_list message - * - * @return Start index. Must be smaller / equal to the largest index of the current onboard list. - */ -static inline int16_t mavlink_msg_mission_write_partial_list_get_start_index(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 0); -} - -/** - * @brief Get field end_index from mission_write_partial_list message - * - * @return End index, equal or greater than start index. - */ -static inline int16_t mavlink_msg_mission_write_partial_list_get_end_index(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 2); -} - -/** - * @brief Get field mission_type from mission_write_partial_list message - * - * @return Mission type. - */ -static inline uint8_t mavlink_msg_mission_write_partial_list_get_mission_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 6); -} - -/** - * @brief Decode a mission_write_partial_list message into a struct - * - * @param msg The message to decode - * @param mission_write_partial_list C-struct to decode the message contents into - */ -static inline void mavlink_msg_mission_write_partial_list_decode(const mavlink_message_t* msg, mavlink_mission_write_partial_list_t* mission_write_partial_list) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mission_write_partial_list->start_index = mavlink_msg_mission_write_partial_list_get_start_index(msg); - mission_write_partial_list->end_index = mavlink_msg_mission_write_partial_list_get_end_index(msg); - mission_write_partial_list->target_system = mavlink_msg_mission_write_partial_list_get_target_system(msg); - mission_write_partial_list->target_component = mavlink_msg_mission_write_partial_list_get_target_component(msg); - mission_write_partial_list->mission_type = mavlink_msg_mission_write_partial_list_get_mission_type(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN? msg->len : MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN; - memset(mission_write_partial_list, 0, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN); - memcpy(mission_write_partial_list, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_mount_orientation.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_mount_orientation.h deleted file mode 100644 index 820f4529..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_mount_orientation.h +++ /dev/null @@ -1,313 +0,0 @@ -#pragma once -// MESSAGE MOUNT_ORIENTATION PACKING - -#define MAVLINK_MSG_ID_MOUNT_ORIENTATION 265 - - -typedef struct __mavlink_mount_orientation_t { - uint32_t time_boot_ms; /*< [ms] Timestamp (time since system boot).*/ - float roll; /*< [deg] Roll in global frame (set to NaN for invalid).*/ - float pitch; /*< [deg] Pitch in global frame (set to NaN for invalid).*/ - float yaw; /*< [deg] Yaw relative to vehicle (set to NaN for invalid).*/ - float yaw_absolute; /*< [deg] Yaw in absolute frame relative to Earth's North, north is 0 (set to NaN for invalid).*/ -} mavlink_mount_orientation_t; - -#define MAVLINK_MSG_ID_MOUNT_ORIENTATION_LEN 20 -#define MAVLINK_MSG_ID_MOUNT_ORIENTATION_MIN_LEN 16 -#define MAVLINK_MSG_ID_265_LEN 20 -#define MAVLINK_MSG_ID_265_MIN_LEN 16 - -#define MAVLINK_MSG_ID_MOUNT_ORIENTATION_CRC 26 -#define MAVLINK_MSG_ID_265_CRC 26 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_MOUNT_ORIENTATION { \ - 265, \ - "MOUNT_ORIENTATION", \ - 5, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_mount_orientation_t, time_boot_ms) }, \ - { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_mount_orientation_t, roll) }, \ - { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_mount_orientation_t, pitch) }, \ - { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_mount_orientation_t, yaw) }, \ - { "yaw_absolute", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_mount_orientation_t, yaw_absolute) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_MOUNT_ORIENTATION { \ - "MOUNT_ORIENTATION", \ - 5, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_mount_orientation_t, time_boot_ms) }, \ - { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_mount_orientation_t, roll) }, \ - { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_mount_orientation_t, pitch) }, \ - { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_mount_orientation_t, yaw) }, \ - { "yaw_absolute", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_mount_orientation_t, yaw_absolute) }, \ - } \ -} -#endif - -/** - * @brief Pack a mount_orientation message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param time_boot_ms [ms] Timestamp (time since system boot). - * @param roll [deg] Roll in global frame (set to NaN for invalid). - * @param pitch [deg] Pitch in global frame (set to NaN for invalid). - * @param yaw [deg] Yaw relative to vehicle (set to NaN for invalid). - * @param yaw_absolute [deg] Yaw in absolute frame relative to Earth's North, north is 0 (set to NaN for invalid). - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_mount_orientation_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint32_t time_boot_ms, float roll, float pitch, float yaw, float yaw_absolute) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MOUNT_ORIENTATION_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, roll); - _mav_put_float(buf, 8, pitch); - _mav_put_float(buf, 12, yaw); - _mav_put_float(buf, 16, yaw_absolute); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MOUNT_ORIENTATION_LEN); -#else - mavlink_mount_orientation_t packet; - packet.time_boot_ms = time_boot_ms; - packet.roll = roll; - packet.pitch = pitch; - packet.yaw = yaw; - packet.yaw_absolute = yaw_absolute; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MOUNT_ORIENTATION_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_MOUNT_ORIENTATION; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MOUNT_ORIENTATION_MIN_LEN, MAVLINK_MSG_ID_MOUNT_ORIENTATION_LEN, MAVLINK_MSG_ID_MOUNT_ORIENTATION_CRC); -} - -/** - * @brief Pack a mount_orientation message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_boot_ms [ms] Timestamp (time since system boot). - * @param roll [deg] Roll in global frame (set to NaN for invalid). - * @param pitch [deg] Pitch in global frame (set to NaN for invalid). - * @param yaw [deg] Yaw relative to vehicle (set to NaN for invalid). - * @param yaw_absolute [deg] Yaw in absolute frame relative to Earth's North, north is 0 (set to NaN for invalid). - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_mount_orientation_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint32_t time_boot_ms,float roll,float pitch,float yaw,float yaw_absolute) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MOUNT_ORIENTATION_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, roll); - _mav_put_float(buf, 8, pitch); - _mav_put_float(buf, 12, yaw); - _mav_put_float(buf, 16, yaw_absolute); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MOUNT_ORIENTATION_LEN); -#else - mavlink_mount_orientation_t packet; - packet.time_boot_ms = time_boot_ms; - packet.roll = roll; - packet.pitch = pitch; - packet.yaw = yaw; - packet.yaw_absolute = yaw_absolute; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MOUNT_ORIENTATION_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_MOUNT_ORIENTATION; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MOUNT_ORIENTATION_MIN_LEN, MAVLINK_MSG_ID_MOUNT_ORIENTATION_LEN, MAVLINK_MSG_ID_MOUNT_ORIENTATION_CRC); -} - -/** - * @brief Encode a mount_orientation struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param mount_orientation C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_mount_orientation_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mount_orientation_t* mount_orientation) -{ - return mavlink_msg_mount_orientation_pack(system_id, component_id, msg, mount_orientation->time_boot_ms, mount_orientation->roll, mount_orientation->pitch, mount_orientation->yaw, mount_orientation->yaw_absolute); -} - -/** - * @brief Encode a mount_orientation struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param mount_orientation C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_mount_orientation_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mount_orientation_t* mount_orientation) -{ - return mavlink_msg_mount_orientation_pack_chan(system_id, component_id, chan, msg, mount_orientation->time_boot_ms, mount_orientation->roll, mount_orientation->pitch, mount_orientation->yaw, mount_orientation->yaw_absolute); -} - -/** - * @brief Send a mount_orientation message - * @param chan MAVLink channel to send the message - * - * @param time_boot_ms [ms] Timestamp (time since system boot). - * @param roll [deg] Roll in global frame (set to NaN for invalid). - * @param pitch [deg] Pitch in global frame (set to NaN for invalid). - * @param yaw [deg] Yaw relative to vehicle (set to NaN for invalid). - * @param yaw_absolute [deg] Yaw in absolute frame relative to Earth's North, north is 0 (set to NaN for invalid). - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_mount_orientation_send(mavlink_channel_t chan, uint32_t time_boot_ms, float roll, float pitch, float yaw, float yaw_absolute) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MOUNT_ORIENTATION_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, roll); - _mav_put_float(buf, 8, pitch); - _mav_put_float(buf, 12, yaw); - _mav_put_float(buf, 16, yaw_absolute); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOUNT_ORIENTATION, buf, MAVLINK_MSG_ID_MOUNT_ORIENTATION_MIN_LEN, MAVLINK_MSG_ID_MOUNT_ORIENTATION_LEN, MAVLINK_MSG_ID_MOUNT_ORIENTATION_CRC); -#else - mavlink_mount_orientation_t packet; - packet.time_boot_ms = time_boot_ms; - packet.roll = roll; - packet.pitch = pitch; - packet.yaw = yaw; - packet.yaw_absolute = yaw_absolute; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOUNT_ORIENTATION, (const char *)&packet, MAVLINK_MSG_ID_MOUNT_ORIENTATION_MIN_LEN, MAVLINK_MSG_ID_MOUNT_ORIENTATION_LEN, MAVLINK_MSG_ID_MOUNT_ORIENTATION_CRC); -#endif -} - -/** - * @brief Send a mount_orientation message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_mount_orientation_send_struct(mavlink_channel_t chan, const mavlink_mount_orientation_t* mount_orientation) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_mount_orientation_send(chan, mount_orientation->time_boot_ms, mount_orientation->roll, mount_orientation->pitch, mount_orientation->yaw, mount_orientation->yaw_absolute); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOUNT_ORIENTATION, (const char *)mount_orientation, MAVLINK_MSG_ID_MOUNT_ORIENTATION_MIN_LEN, MAVLINK_MSG_ID_MOUNT_ORIENTATION_LEN, MAVLINK_MSG_ID_MOUNT_ORIENTATION_CRC); -#endif -} - -#if MAVLINK_MSG_ID_MOUNT_ORIENTATION_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_mount_orientation_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, float roll, float pitch, float yaw, float yaw_absolute) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, roll); - _mav_put_float(buf, 8, pitch); - _mav_put_float(buf, 12, yaw); - _mav_put_float(buf, 16, yaw_absolute); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOUNT_ORIENTATION, buf, MAVLINK_MSG_ID_MOUNT_ORIENTATION_MIN_LEN, MAVLINK_MSG_ID_MOUNT_ORIENTATION_LEN, MAVLINK_MSG_ID_MOUNT_ORIENTATION_CRC); -#else - mavlink_mount_orientation_t *packet = (mavlink_mount_orientation_t *)msgbuf; - packet->time_boot_ms = time_boot_ms; - packet->roll = roll; - packet->pitch = pitch; - packet->yaw = yaw; - packet->yaw_absolute = yaw_absolute; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOUNT_ORIENTATION, (const char *)packet, MAVLINK_MSG_ID_MOUNT_ORIENTATION_MIN_LEN, MAVLINK_MSG_ID_MOUNT_ORIENTATION_LEN, MAVLINK_MSG_ID_MOUNT_ORIENTATION_CRC); -#endif -} -#endif - -#endif - -// MESSAGE MOUNT_ORIENTATION UNPACKING - - -/** - * @brief Get field time_boot_ms from mount_orientation message - * - * @return [ms] Timestamp (time since system boot). - */ -static inline uint32_t mavlink_msg_mount_orientation_get_time_boot_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field roll from mount_orientation message - * - * @return [deg] Roll in global frame (set to NaN for invalid). - */ -static inline float mavlink_msg_mount_orientation_get_roll(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 4); -} - -/** - * @brief Get field pitch from mount_orientation message - * - * @return [deg] Pitch in global frame (set to NaN for invalid). - */ -static inline float mavlink_msg_mount_orientation_get_pitch(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field yaw from mount_orientation message - * - * @return [deg] Yaw relative to vehicle (set to NaN for invalid). - */ -static inline float mavlink_msg_mount_orientation_get_yaw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field yaw_absolute from mount_orientation message - * - * @return [deg] Yaw in absolute frame relative to Earth's North, north is 0 (set to NaN for invalid). - */ -static inline float mavlink_msg_mount_orientation_get_yaw_absolute(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Decode a mount_orientation message into a struct - * - * @param msg The message to decode - * @param mount_orientation C-struct to decode the message contents into - */ -static inline void mavlink_msg_mount_orientation_decode(const mavlink_message_t* msg, mavlink_mount_orientation_t* mount_orientation) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mount_orientation->time_boot_ms = mavlink_msg_mount_orientation_get_time_boot_ms(msg); - mount_orientation->roll = mavlink_msg_mount_orientation_get_roll(msg); - mount_orientation->pitch = mavlink_msg_mount_orientation_get_pitch(msg); - mount_orientation->yaw = mavlink_msg_mount_orientation_get_yaw(msg); - mount_orientation->yaw_absolute = mavlink_msg_mount_orientation_get_yaw_absolute(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_MOUNT_ORIENTATION_LEN? msg->len : MAVLINK_MSG_ID_MOUNT_ORIENTATION_LEN; - memset(mount_orientation, 0, MAVLINK_MSG_ID_MOUNT_ORIENTATION_LEN); - memcpy(mount_orientation, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_named_value_float.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_named_value_float.h deleted file mode 100644 index fe75e782..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_named_value_float.h +++ /dev/null @@ -1,255 +0,0 @@ -#pragma once -// MESSAGE NAMED_VALUE_FLOAT PACKING - -#define MAVLINK_MSG_ID_NAMED_VALUE_FLOAT 251 - - -typedef struct __mavlink_named_value_float_t { - uint32_t time_boot_ms; /*< [ms] Timestamp (time since system boot).*/ - float value; /*< Floating point value*/ - char name[10]; /*< Name of the debug variable*/ -} mavlink_named_value_float_t; - -#define MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN 18 -#define MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_MIN_LEN 18 -#define MAVLINK_MSG_ID_251_LEN 18 -#define MAVLINK_MSG_ID_251_MIN_LEN 18 - -#define MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_CRC 170 -#define MAVLINK_MSG_ID_251_CRC 170 - -#define MAVLINK_MSG_NAMED_VALUE_FLOAT_FIELD_NAME_LEN 10 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_NAMED_VALUE_FLOAT { \ - 251, \ - "NAMED_VALUE_FLOAT", \ - 3, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_named_value_float_t, time_boot_ms) }, \ - { "name", NULL, MAVLINK_TYPE_CHAR, 10, 8, offsetof(mavlink_named_value_float_t, name) }, \ - { "value", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_named_value_float_t, value) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_NAMED_VALUE_FLOAT { \ - "NAMED_VALUE_FLOAT", \ - 3, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_named_value_float_t, time_boot_ms) }, \ - { "name", NULL, MAVLINK_TYPE_CHAR, 10, 8, offsetof(mavlink_named_value_float_t, name) }, \ - { "value", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_named_value_float_t, value) }, \ - } \ -} -#endif - -/** - * @brief Pack a named_value_float message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param time_boot_ms [ms] Timestamp (time since system boot). - * @param name Name of the debug variable - * @param value Floating point value - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_named_value_float_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint32_t time_boot_ms, const char *name, float value) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, value); - _mav_put_char_array(buf, 8, name, 10); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN); -#else - mavlink_named_value_float_t packet; - packet.time_boot_ms = time_boot_ms; - packet.value = value; - mav_array_memcpy(packet.name, name, sizeof(char)*10); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_NAMED_VALUE_FLOAT; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_MIN_LEN, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_CRC); -} - -/** - * @brief Pack a named_value_float message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_boot_ms [ms] Timestamp (time since system boot). - * @param name Name of the debug variable - * @param value Floating point value - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_named_value_float_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint32_t time_boot_ms,const char *name,float value) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, value); - _mav_put_char_array(buf, 8, name, 10); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN); -#else - mavlink_named_value_float_t packet; - packet.time_boot_ms = time_boot_ms; - packet.value = value; - mav_array_memcpy(packet.name, name, sizeof(char)*10); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_NAMED_VALUE_FLOAT; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_MIN_LEN, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_CRC); -} - -/** - * @brief Encode a named_value_float struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param named_value_float C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_named_value_float_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_named_value_float_t* named_value_float) -{ - return mavlink_msg_named_value_float_pack(system_id, component_id, msg, named_value_float->time_boot_ms, named_value_float->name, named_value_float->value); -} - -/** - * @brief Encode a named_value_float struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param named_value_float C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_named_value_float_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_named_value_float_t* named_value_float) -{ - return mavlink_msg_named_value_float_pack_chan(system_id, component_id, chan, msg, named_value_float->time_boot_ms, named_value_float->name, named_value_float->value); -} - -/** - * @brief Send a named_value_float message - * @param chan MAVLink channel to send the message - * - * @param time_boot_ms [ms] Timestamp (time since system boot). - * @param name Name of the debug variable - * @param value Floating point value - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_named_value_float_send(mavlink_channel_t chan, uint32_t time_boot_ms, const char *name, float value) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, value); - _mav_put_char_array(buf, 8, name, 10); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT, buf, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_MIN_LEN, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_CRC); -#else - mavlink_named_value_float_t packet; - packet.time_boot_ms = time_boot_ms; - packet.value = value; - mav_array_memcpy(packet.name, name, sizeof(char)*10); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT, (const char *)&packet, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_MIN_LEN, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_CRC); -#endif -} - -/** - * @brief Send a named_value_float message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_named_value_float_send_struct(mavlink_channel_t chan, const mavlink_named_value_float_t* named_value_float) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_named_value_float_send(chan, named_value_float->time_boot_ms, named_value_float->name, named_value_float->value); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT, (const char *)named_value_float, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_MIN_LEN, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_CRC); -#endif -} - -#if MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_named_value_float_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, const char *name, float value) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, value); - _mav_put_char_array(buf, 8, name, 10); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT, buf, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_MIN_LEN, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_CRC); -#else - mavlink_named_value_float_t *packet = (mavlink_named_value_float_t *)msgbuf; - packet->time_boot_ms = time_boot_ms; - packet->value = value; - mav_array_memcpy(packet->name, name, sizeof(char)*10); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT, (const char *)packet, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_MIN_LEN, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_CRC); -#endif -} -#endif - -#endif - -// MESSAGE NAMED_VALUE_FLOAT UNPACKING - - -/** - * @brief Get field time_boot_ms from named_value_float message - * - * @return [ms] Timestamp (time since system boot). - */ -static inline uint32_t mavlink_msg_named_value_float_get_time_boot_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field name from named_value_float message - * - * @return Name of the debug variable - */ -static inline uint16_t mavlink_msg_named_value_float_get_name(const mavlink_message_t* msg, char *name) -{ - return _MAV_RETURN_char_array(msg, name, 10, 8); -} - -/** - * @brief Get field value from named_value_float message - * - * @return Floating point value - */ -static inline float mavlink_msg_named_value_float_get_value(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 4); -} - -/** - * @brief Decode a named_value_float message into a struct - * - * @param msg The message to decode - * @param named_value_float C-struct to decode the message contents into - */ -static inline void mavlink_msg_named_value_float_decode(const mavlink_message_t* msg, mavlink_named_value_float_t* named_value_float) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - named_value_float->time_boot_ms = mavlink_msg_named_value_float_get_time_boot_ms(msg); - named_value_float->value = mavlink_msg_named_value_float_get_value(msg); - mavlink_msg_named_value_float_get_name(msg, named_value_float->name); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN? msg->len : MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN; - memset(named_value_float, 0, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN); - memcpy(named_value_float, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_named_value_int.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_named_value_int.h deleted file mode 100644 index f33d7f4d..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_named_value_int.h +++ /dev/null @@ -1,255 +0,0 @@ -#pragma once -// MESSAGE NAMED_VALUE_INT PACKING - -#define MAVLINK_MSG_ID_NAMED_VALUE_INT 252 - - -typedef struct __mavlink_named_value_int_t { - uint32_t time_boot_ms; /*< [ms] Timestamp (time since system boot).*/ - int32_t value; /*< Signed integer value*/ - char name[10]; /*< Name of the debug variable*/ -} mavlink_named_value_int_t; - -#define MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN 18 -#define MAVLINK_MSG_ID_NAMED_VALUE_INT_MIN_LEN 18 -#define MAVLINK_MSG_ID_252_LEN 18 -#define MAVLINK_MSG_ID_252_MIN_LEN 18 - -#define MAVLINK_MSG_ID_NAMED_VALUE_INT_CRC 44 -#define MAVLINK_MSG_ID_252_CRC 44 - -#define MAVLINK_MSG_NAMED_VALUE_INT_FIELD_NAME_LEN 10 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_NAMED_VALUE_INT { \ - 252, \ - "NAMED_VALUE_INT", \ - 3, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_named_value_int_t, time_boot_ms) }, \ - { "name", NULL, MAVLINK_TYPE_CHAR, 10, 8, offsetof(mavlink_named_value_int_t, name) }, \ - { "value", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_named_value_int_t, value) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_NAMED_VALUE_INT { \ - "NAMED_VALUE_INT", \ - 3, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_named_value_int_t, time_boot_ms) }, \ - { "name", NULL, MAVLINK_TYPE_CHAR, 10, 8, offsetof(mavlink_named_value_int_t, name) }, \ - { "value", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_named_value_int_t, value) }, \ - } \ -} -#endif - -/** - * @brief Pack a named_value_int message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param time_boot_ms [ms] Timestamp (time since system boot). - * @param name Name of the debug variable - * @param value Signed integer value - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_named_value_int_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint32_t time_boot_ms, const char *name, int32_t value) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_int32_t(buf, 4, value); - _mav_put_char_array(buf, 8, name, 10); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN); -#else - mavlink_named_value_int_t packet; - packet.time_boot_ms = time_boot_ms; - packet.value = value; - mav_array_memcpy(packet.name, name, sizeof(char)*10); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_NAMED_VALUE_INT; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_NAMED_VALUE_INT_MIN_LEN, MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN, MAVLINK_MSG_ID_NAMED_VALUE_INT_CRC); -} - -/** - * @brief Pack a named_value_int message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_boot_ms [ms] Timestamp (time since system boot). - * @param name Name of the debug variable - * @param value Signed integer value - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_named_value_int_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint32_t time_boot_ms,const char *name,int32_t value) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_int32_t(buf, 4, value); - _mav_put_char_array(buf, 8, name, 10); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN); -#else - mavlink_named_value_int_t packet; - packet.time_boot_ms = time_boot_ms; - packet.value = value; - mav_array_memcpy(packet.name, name, sizeof(char)*10); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_NAMED_VALUE_INT; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_NAMED_VALUE_INT_MIN_LEN, MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN, MAVLINK_MSG_ID_NAMED_VALUE_INT_CRC); -} - -/** - * @brief Encode a named_value_int struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param named_value_int C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_named_value_int_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_named_value_int_t* named_value_int) -{ - return mavlink_msg_named_value_int_pack(system_id, component_id, msg, named_value_int->time_boot_ms, named_value_int->name, named_value_int->value); -} - -/** - * @brief Encode a named_value_int struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param named_value_int C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_named_value_int_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_named_value_int_t* named_value_int) -{ - return mavlink_msg_named_value_int_pack_chan(system_id, component_id, chan, msg, named_value_int->time_boot_ms, named_value_int->name, named_value_int->value); -} - -/** - * @brief Send a named_value_int message - * @param chan MAVLink channel to send the message - * - * @param time_boot_ms [ms] Timestamp (time since system boot). - * @param name Name of the debug variable - * @param value Signed integer value - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_named_value_int_send(mavlink_channel_t chan, uint32_t time_boot_ms, const char *name, int32_t value) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_int32_t(buf, 4, value); - _mav_put_char_array(buf, 8, name, 10); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_VALUE_INT, buf, MAVLINK_MSG_ID_NAMED_VALUE_INT_MIN_LEN, MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN, MAVLINK_MSG_ID_NAMED_VALUE_INT_CRC); -#else - mavlink_named_value_int_t packet; - packet.time_boot_ms = time_boot_ms; - packet.value = value; - mav_array_memcpy(packet.name, name, sizeof(char)*10); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_VALUE_INT, (const char *)&packet, MAVLINK_MSG_ID_NAMED_VALUE_INT_MIN_LEN, MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN, MAVLINK_MSG_ID_NAMED_VALUE_INT_CRC); -#endif -} - -/** - * @brief Send a named_value_int message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_named_value_int_send_struct(mavlink_channel_t chan, const mavlink_named_value_int_t* named_value_int) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_named_value_int_send(chan, named_value_int->time_boot_ms, named_value_int->name, named_value_int->value); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_VALUE_INT, (const char *)named_value_int, MAVLINK_MSG_ID_NAMED_VALUE_INT_MIN_LEN, MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN, MAVLINK_MSG_ID_NAMED_VALUE_INT_CRC); -#endif -} - -#if MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_named_value_int_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, const char *name, int32_t value) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_int32_t(buf, 4, value); - _mav_put_char_array(buf, 8, name, 10); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_VALUE_INT, buf, MAVLINK_MSG_ID_NAMED_VALUE_INT_MIN_LEN, MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN, MAVLINK_MSG_ID_NAMED_VALUE_INT_CRC); -#else - mavlink_named_value_int_t *packet = (mavlink_named_value_int_t *)msgbuf; - packet->time_boot_ms = time_boot_ms; - packet->value = value; - mav_array_memcpy(packet->name, name, sizeof(char)*10); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_VALUE_INT, (const char *)packet, MAVLINK_MSG_ID_NAMED_VALUE_INT_MIN_LEN, MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN, MAVLINK_MSG_ID_NAMED_VALUE_INT_CRC); -#endif -} -#endif - -#endif - -// MESSAGE NAMED_VALUE_INT UNPACKING - - -/** - * @brief Get field time_boot_ms from named_value_int message - * - * @return [ms] Timestamp (time since system boot). - */ -static inline uint32_t mavlink_msg_named_value_int_get_time_boot_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field name from named_value_int message - * - * @return Name of the debug variable - */ -static inline uint16_t mavlink_msg_named_value_int_get_name(const mavlink_message_t* msg, char *name) -{ - return _MAV_RETURN_char_array(msg, name, 10, 8); -} - -/** - * @brief Get field value from named_value_int message - * - * @return Signed integer value - */ -static inline int32_t mavlink_msg_named_value_int_get_value(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 4); -} - -/** - * @brief Decode a named_value_int message into a struct - * - * @param msg The message to decode - * @param named_value_int C-struct to decode the message contents into - */ -static inline void mavlink_msg_named_value_int_decode(const mavlink_message_t* msg, mavlink_named_value_int_t* named_value_int) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - named_value_int->time_boot_ms = mavlink_msg_named_value_int_get_time_boot_ms(msg); - named_value_int->value = mavlink_msg_named_value_int_get_value(msg); - mavlink_msg_named_value_int_get_name(msg, named_value_int->name); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN? msg->len : MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN; - memset(named_value_int, 0, MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN); - memcpy(named_value_int, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_nav_controller_output.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_nav_controller_output.h deleted file mode 100644 index 1e29b77d..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_nav_controller_output.h +++ /dev/null @@ -1,388 +0,0 @@ -#pragma once -// MESSAGE NAV_CONTROLLER_OUTPUT PACKING - -#define MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT 62 - - -typedef struct __mavlink_nav_controller_output_t { - float nav_roll; /*< [deg] Current desired roll*/ - float nav_pitch; /*< [deg] Current desired pitch*/ - float alt_error; /*< [m] Current altitude error*/ - float aspd_error; /*< [m/s] Current airspeed error*/ - float xtrack_error; /*< [m] Current crosstrack error on x-y plane*/ - int16_t nav_bearing; /*< [deg] Current desired heading*/ - int16_t target_bearing; /*< [deg] Bearing to current waypoint/target*/ - uint16_t wp_dist; /*< [m] Distance to active waypoint*/ -} mavlink_nav_controller_output_t; - -#define MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN 26 -#define MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_MIN_LEN 26 -#define MAVLINK_MSG_ID_62_LEN 26 -#define MAVLINK_MSG_ID_62_MIN_LEN 26 - -#define MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_CRC 183 -#define MAVLINK_MSG_ID_62_CRC 183 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_NAV_CONTROLLER_OUTPUT { \ - 62, \ - "NAV_CONTROLLER_OUTPUT", \ - 8, \ - { { "nav_roll", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_nav_controller_output_t, nav_roll) }, \ - { "nav_pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_nav_controller_output_t, nav_pitch) }, \ - { "nav_bearing", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_nav_controller_output_t, nav_bearing) }, \ - { "target_bearing", NULL, MAVLINK_TYPE_INT16_T, 0, 22, offsetof(mavlink_nav_controller_output_t, target_bearing) }, \ - { "wp_dist", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_nav_controller_output_t, wp_dist) }, \ - { "alt_error", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_nav_controller_output_t, alt_error) }, \ - { "aspd_error", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_nav_controller_output_t, aspd_error) }, \ - { "xtrack_error", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_nav_controller_output_t, xtrack_error) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_NAV_CONTROLLER_OUTPUT { \ - "NAV_CONTROLLER_OUTPUT", \ - 8, \ - { { "nav_roll", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_nav_controller_output_t, nav_roll) }, \ - { "nav_pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_nav_controller_output_t, nav_pitch) }, \ - { "nav_bearing", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_nav_controller_output_t, nav_bearing) }, \ - { "target_bearing", NULL, MAVLINK_TYPE_INT16_T, 0, 22, offsetof(mavlink_nav_controller_output_t, target_bearing) }, \ - { "wp_dist", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_nav_controller_output_t, wp_dist) }, \ - { "alt_error", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_nav_controller_output_t, alt_error) }, \ - { "aspd_error", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_nav_controller_output_t, aspd_error) }, \ - { "xtrack_error", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_nav_controller_output_t, xtrack_error) }, \ - } \ -} -#endif - -/** - * @brief Pack a nav_controller_output message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param nav_roll [deg] Current desired roll - * @param nav_pitch [deg] Current desired pitch - * @param nav_bearing [deg] Current desired heading - * @param target_bearing [deg] Bearing to current waypoint/target - * @param wp_dist [m] Distance to active waypoint - * @param alt_error [m] Current altitude error - * @param aspd_error [m/s] Current airspeed error - * @param xtrack_error [m] Current crosstrack error on x-y plane - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_nav_controller_output_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - float nav_roll, float nav_pitch, int16_t nav_bearing, int16_t target_bearing, uint16_t wp_dist, float alt_error, float aspd_error, float xtrack_error) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN]; - _mav_put_float(buf, 0, nav_roll); - _mav_put_float(buf, 4, nav_pitch); - _mav_put_float(buf, 8, alt_error); - _mav_put_float(buf, 12, aspd_error); - _mav_put_float(buf, 16, xtrack_error); - _mav_put_int16_t(buf, 20, nav_bearing); - _mav_put_int16_t(buf, 22, target_bearing); - _mav_put_uint16_t(buf, 24, wp_dist); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN); -#else - mavlink_nav_controller_output_t packet; - packet.nav_roll = nav_roll; - packet.nav_pitch = nav_pitch; - packet.alt_error = alt_error; - packet.aspd_error = aspd_error; - packet.xtrack_error = xtrack_error; - packet.nav_bearing = nav_bearing; - packet.target_bearing = target_bearing; - packet.wp_dist = wp_dist; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_MIN_LEN, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_CRC); -} - -/** - * @brief Pack a nav_controller_output message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param nav_roll [deg] Current desired roll - * @param nav_pitch [deg] Current desired pitch - * @param nav_bearing [deg] Current desired heading - * @param target_bearing [deg] Bearing to current waypoint/target - * @param wp_dist [m] Distance to active waypoint - * @param alt_error [m] Current altitude error - * @param aspd_error [m/s] Current airspeed error - * @param xtrack_error [m] Current crosstrack error on x-y plane - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_nav_controller_output_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - float nav_roll,float nav_pitch,int16_t nav_bearing,int16_t target_bearing,uint16_t wp_dist,float alt_error,float aspd_error,float xtrack_error) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN]; - _mav_put_float(buf, 0, nav_roll); - _mav_put_float(buf, 4, nav_pitch); - _mav_put_float(buf, 8, alt_error); - _mav_put_float(buf, 12, aspd_error); - _mav_put_float(buf, 16, xtrack_error); - _mav_put_int16_t(buf, 20, nav_bearing); - _mav_put_int16_t(buf, 22, target_bearing); - _mav_put_uint16_t(buf, 24, wp_dist); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN); -#else - mavlink_nav_controller_output_t packet; - packet.nav_roll = nav_roll; - packet.nav_pitch = nav_pitch; - packet.alt_error = alt_error; - packet.aspd_error = aspd_error; - packet.xtrack_error = xtrack_error; - packet.nav_bearing = nav_bearing; - packet.target_bearing = target_bearing; - packet.wp_dist = wp_dist; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_MIN_LEN, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_CRC); -} - -/** - * @brief Encode a nav_controller_output struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param nav_controller_output C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_nav_controller_output_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_nav_controller_output_t* nav_controller_output) -{ - return mavlink_msg_nav_controller_output_pack(system_id, component_id, msg, nav_controller_output->nav_roll, nav_controller_output->nav_pitch, nav_controller_output->nav_bearing, nav_controller_output->target_bearing, nav_controller_output->wp_dist, nav_controller_output->alt_error, nav_controller_output->aspd_error, nav_controller_output->xtrack_error); -} - -/** - * @brief Encode a nav_controller_output struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param nav_controller_output C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_nav_controller_output_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_nav_controller_output_t* nav_controller_output) -{ - return mavlink_msg_nav_controller_output_pack_chan(system_id, component_id, chan, msg, nav_controller_output->nav_roll, nav_controller_output->nav_pitch, nav_controller_output->nav_bearing, nav_controller_output->target_bearing, nav_controller_output->wp_dist, nav_controller_output->alt_error, nav_controller_output->aspd_error, nav_controller_output->xtrack_error); -} - -/** - * @brief Send a nav_controller_output message - * @param chan MAVLink channel to send the message - * - * @param nav_roll [deg] Current desired roll - * @param nav_pitch [deg] Current desired pitch - * @param nav_bearing [deg] Current desired heading - * @param target_bearing [deg] Bearing to current waypoint/target - * @param wp_dist [m] Distance to active waypoint - * @param alt_error [m] Current altitude error - * @param aspd_error [m/s] Current airspeed error - * @param xtrack_error [m] Current crosstrack error on x-y plane - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_nav_controller_output_send(mavlink_channel_t chan, float nav_roll, float nav_pitch, int16_t nav_bearing, int16_t target_bearing, uint16_t wp_dist, float alt_error, float aspd_error, float xtrack_error) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN]; - _mav_put_float(buf, 0, nav_roll); - _mav_put_float(buf, 4, nav_pitch); - _mav_put_float(buf, 8, alt_error); - _mav_put_float(buf, 12, aspd_error); - _mav_put_float(buf, 16, xtrack_error); - _mav_put_int16_t(buf, 20, nav_bearing); - _mav_put_int16_t(buf, 22, target_bearing); - _mav_put_uint16_t(buf, 24, wp_dist); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT, buf, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_MIN_LEN, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_CRC); -#else - mavlink_nav_controller_output_t packet; - packet.nav_roll = nav_roll; - packet.nav_pitch = nav_pitch; - packet.alt_error = alt_error; - packet.aspd_error = aspd_error; - packet.xtrack_error = xtrack_error; - packet.nav_bearing = nav_bearing; - packet.target_bearing = target_bearing; - packet.wp_dist = wp_dist; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT, (const char *)&packet, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_MIN_LEN, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_CRC); -#endif -} - -/** - * @brief Send a nav_controller_output message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_nav_controller_output_send_struct(mavlink_channel_t chan, const mavlink_nav_controller_output_t* nav_controller_output) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_nav_controller_output_send(chan, nav_controller_output->nav_roll, nav_controller_output->nav_pitch, nav_controller_output->nav_bearing, nav_controller_output->target_bearing, nav_controller_output->wp_dist, nav_controller_output->alt_error, nav_controller_output->aspd_error, nav_controller_output->xtrack_error); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT, (const char *)nav_controller_output, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_MIN_LEN, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_CRC); -#endif -} - -#if MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_nav_controller_output_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, float nav_roll, float nav_pitch, int16_t nav_bearing, int16_t target_bearing, uint16_t wp_dist, float alt_error, float aspd_error, float xtrack_error) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_float(buf, 0, nav_roll); - _mav_put_float(buf, 4, nav_pitch); - _mav_put_float(buf, 8, alt_error); - _mav_put_float(buf, 12, aspd_error); - _mav_put_float(buf, 16, xtrack_error); - _mav_put_int16_t(buf, 20, nav_bearing); - _mav_put_int16_t(buf, 22, target_bearing); - _mav_put_uint16_t(buf, 24, wp_dist); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT, buf, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_MIN_LEN, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_CRC); -#else - mavlink_nav_controller_output_t *packet = (mavlink_nav_controller_output_t *)msgbuf; - packet->nav_roll = nav_roll; - packet->nav_pitch = nav_pitch; - packet->alt_error = alt_error; - packet->aspd_error = aspd_error; - packet->xtrack_error = xtrack_error; - packet->nav_bearing = nav_bearing; - packet->target_bearing = target_bearing; - packet->wp_dist = wp_dist; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT, (const char *)packet, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_MIN_LEN, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_CRC); -#endif -} -#endif - -#endif - -// MESSAGE NAV_CONTROLLER_OUTPUT UNPACKING - - -/** - * @brief Get field nav_roll from nav_controller_output message - * - * @return [deg] Current desired roll - */ -static inline float mavlink_msg_nav_controller_output_get_nav_roll(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 0); -} - -/** - * @brief Get field nav_pitch from nav_controller_output message - * - * @return [deg] Current desired pitch - */ -static inline float mavlink_msg_nav_controller_output_get_nav_pitch(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 4); -} - -/** - * @brief Get field nav_bearing from nav_controller_output message - * - * @return [deg] Current desired heading - */ -static inline int16_t mavlink_msg_nav_controller_output_get_nav_bearing(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 20); -} - -/** - * @brief Get field target_bearing from nav_controller_output message - * - * @return [deg] Bearing to current waypoint/target - */ -static inline int16_t mavlink_msg_nav_controller_output_get_target_bearing(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 22); -} - -/** - * @brief Get field wp_dist from nav_controller_output message - * - * @return [m] Distance to active waypoint - */ -static inline uint16_t mavlink_msg_nav_controller_output_get_wp_dist(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 24); -} - -/** - * @brief Get field alt_error from nav_controller_output message - * - * @return [m] Current altitude error - */ -static inline float mavlink_msg_nav_controller_output_get_alt_error(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field aspd_error from nav_controller_output message - * - * @return [m/s] Current airspeed error - */ -static inline float mavlink_msg_nav_controller_output_get_aspd_error(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field xtrack_error from nav_controller_output message - * - * @return [m] Current crosstrack error on x-y plane - */ -static inline float mavlink_msg_nav_controller_output_get_xtrack_error(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Decode a nav_controller_output message into a struct - * - * @param msg The message to decode - * @param nav_controller_output C-struct to decode the message contents into - */ -static inline void mavlink_msg_nav_controller_output_decode(const mavlink_message_t* msg, mavlink_nav_controller_output_t* nav_controller_output) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - nav_controller_output->nav_roll = mavlink_msg_nav_controller_output_get_nav_roll(msg); - nav_controller_output->nav_pitch = mavlink_msg_nav_controller_output_get_nav_pitch(msg); - nav_controller_output->alt_error = mavlink_msg_nav_controller_output_get_alt_error(msg); - nav_controller_output->aspd_error = mavlink_msg_nav_controller_output_get_aspd_error(msg); - nav_controller_output->xtrack_error = mavlink_msg_nav_controller_output_get_xtrack_error(msg); - nav_controller_output->nav_bearing = mavlink_msg_nav_controller_output_get_nav_bearing(msg); - nav_controller_output->target_bearing = mavlink_msg_nav_controller_output_get_target_bearing(msg); - nav_controller_output->wp_dist = mavlink_msg_nav_controller_output_get_wp_dist(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN? msg->len : MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN; - memset(nav_controller_output, 0, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN); - memcpy(nav_controller_output, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_obstacle_distance.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_obstacle_distance.h deleted file mode 100644 index afc25f14..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_obstacle_distance.h +++ /dev/null @@ -1,405 +0,0 @@ -#pragma once -// MESSAGE OBSTACLE_DISTANCE PACKING - -#define MAVLINK_MSG_ID_OBSTACLE_DISTANCE 330 - -MAVPACKED( -typedef struct __mavlink_obstacle_distance_t { - uint64_t time_usec; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/ - uint16_t distances[72]; /*< [cm] Distance of obstacles around the vehicle with index 0 corresponding to north + angle_offset, unless otherwise specified in the frame. A value of 0 is valid and means that the obstacle is practically touching the sensor. A value of max_distance +1 means no obstacle is present. A value of UINT16_MAX for unknown/not used. In a array element, one unit corresponds to 1cm.*/ - uint16_t min_distance; /*< [cm] Minimum distance the sensor can measure.*/ - uint16_t max_distance; /*< [cm] Maximum distance the sensor can measure.*/ - uint8_t sensor_type; /*< Class id of the distance sensor type.*/ - uint8_t increment; /*< [deg] Angular width in degrees of each array element. Increment direction is clockwise. This field is ignored if increment_f is non-zero.*/ - float increment_f; /*< [deg] Angular width in degrees of each array element as a float. If non-zero then this value is used instead of the uint8_t increment field. Positive is clockwise direction, negative is counter-clockwise.*/ - float angle_offset; /*< [deg] Relative angle offset of the 0-index element in the distances array. Value of 0 corresponds to forward. Positive is clockwise direction, negative is counter-clockwise.*/ - uint8_t frame; /*< Coordinate frame of reference for the yaw rotation and offset of the sensor data. Defaults to MAV_FRAME_GLOBAL, which is north aligned. For body-mounted sensors use MAV_FRAME_BODY_FRD, which is vehicle front aligned.*/ -}) mavlink_obstacle_distance_t; - -#define MAVLINK_MSG_ID_OBSTACLE_DISTANCE_LEN 167 -#define MAVLINK_MSG_ID_OBSTACLE_DISTANCE_MIN_LEN 158 -#define MAVLINK_MSG_ID_330_LEN 167 -#define MAVLINK_MSG_ID_330_MIN_LEN 158 - -#define MAVLINK_MSG_ID_OBSTACLE_DISTANCE_CRC 23 -#define MAVLINK_MSG_ID_330_CRC 23 - -#define MAVLINK_MSG_OBSTACLE_DISTANCE_FIELD_DISTANCES_LEN 72 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_OBSTACLE_DISTANCE { \ - 330, \ - "OBSTACLE_DISTANCE", \ - 9, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_obstacle_distance_t, time_usec) }, \ - { "sensor_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 156, offsetof(mavlink_obstacle_distance_t, sensor_type) }, \ - { "distances", NULL, MAVLINK_TYPE_UINT16_T, 72, 8, offsetof(mavlink_obstacle_distance_t, distances) }, \ - { "increment", NULL, MAVLINK_TYPE_UINT8_T, 0, 157, offsetof(mavlink_obstacle_distance_t, increment) }, \ - { "min_distance", NULL, MAVLINK_TYPE_UINT16_T, 0, 152, offsetof(mavlink_obstacle_distance_t, min_distance) }, \ - { "max_distance", NULL, MAVLINK_TYPE_UINT16_T, 0, 154, offsetof(mavlink_obstacle_distance_t, max_distance) }, \ - { "increment_f", NULL, MAVLINK_TYPE_FLOAT, 0, 158, offsetof(mavlink_obstacle_distance_t, increment_f) }, \ - { "angle_offset", NULL, MAVLINK_TYPE_FLOAT, 0, 162, offsetof(mavlink_obstacle_distance_t, angle_offset) }, \ - { "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 166, offsetof(mavlink_obstacle_distance_t, frame) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_OBSTACLE_DISTANCE { \ - "OBSTACLE_DISTANCE", \ - 9, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_obstacle_distance_t, time_usec) }, \ - { "sensor_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 156, offsetof(mavlink_obstacle_distance_t, sensor_type) }, \ - { "distances", NULL, MAVLINK_TYPE_UINT16_T, 72, 8, offsetof(mavlink_obstacle_distance_t, distances) }, \ - { "increment", NULL, MAVLINK_TYPE_UINT8_T, 0, 157, offsetof(mavlink_obstacle_distance_t, increment) }, \ - { "min_distance", NULL, MAVLINK_TYPE_UINT16_T, 0, 152, offsetof(mavlink_obstacle_distance_t, min_distance) }, \ - { "max_distance", NULL, MAVLINK_TYPE_UINT16_T, 0, 154, offsetof(mavlink_obstacle_distance_t, max_distance) }, \ - { "increment_f", NULL, MAVLINK_TYPE_FLOAT, 0, 158, offsetof(mavlink_obstacle_distance_t, increment_f) }, \ - { "angle_offset", NULL, MAVLINK_TYPE_FLOAT, 0, 162, offsetof(mavlink_obstacle_distance_t, angle_offset) }, \ - { "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 166, offsetof(mavlink_obstacle_distance_t, frame) }, \ - } \ -} -#endif - -/** - * @brief Pack a obstacle_distance message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @param sensor_type Class id of the distance sensor type. - * @param distances [cm] Distance of obstacles around the vehicle with index 0 corresponding to north + angle_offset, unless otherwise specified in the frame. A value of 0 is valid and means that the obstacle is practically touching the sensor. A value of max_distance +1 means no obstacle is present. A value of UINT16_MAX for unknown/not used. In a array element, one unit corresponds to 1cm. - * @param increment [deg] Angular width in degrees of each array element. Increment direction is clockwise. This field is ignored if increment_f is non-zero. - * @param min_distance [cm] Minimum distance the sensor can measure. - * @param max_distance [cm] Maximum distance the sensor can measure. - * @param increment_f [deg] Angular width in degrees of each array element as a float. If non-zero then this value is used instead of the uint8_t increment field. Positive is clockwise direction, negative is counter-clockwise. - * @param angle_offset [deg] Relative angle offset of the 0-index element in the distances array. Value of 0 corresponds to forward. Positive is clockwise direction, negative is counter-clockwise. - * @param frame Coordinate frame of reference for the yaw rotation and offset of the sensor data. Defaults to MAV_FRAME_GLOBAL, which is north aligned. For body-mounted sensors use MAV_FRAME_BODY_FRD, which is vehicle front aligned. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_obstacle_distance_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint64_t time_usec, uint8_t sensor_type, const uint16_t *distances, uint8_t increment, uint16_t min_distance, uint16_t max_distance, float increment_f, float angle_offset, uint8_t frame) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_OBSTACLE_DISTANCE_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint16_t(buf, 152, min_distance); - _mav_put_uint16_t(buf, 154, max_distance); - _mav_put_uint8_t(buf, 156, sensor_type); - _mav_put_uint8_t(buf, 157, increment); - _mav_put_float(buf, 158, increment_f); - _mav_put_float(buf, 162, angle_offset); - _mav_put_uint8_t(buf, 166, frame); - _mav_put_uint16_t_array(buf, 8, distances, 72); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OBSTACLE_DISTANCE_LEN); -#else - mavlink_obstacle_distance_t packet; - packet.time_usec = time_usec; - packet.min_distance = min_distance; - packet.max_distance = max_distance; - packet.sensor_type = sensor_type; - packet.increment = increment; - packet.increment_f = increment_f; - packet.angle_offset = angle_offset; - packet.frame = frame; - mav_array_memcpy(packet.distances, distances, sizeof(uint16_t)*72); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_OBSTACLE_DISTANCE_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_OBSTACLE_DISTANCE; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_OBSTACLE_DISTANCE_MIN_LEN, MAVLINK_MSG_ID_OBSTACLE_DISTANCE_LEN, MAVLINK_MSG_ID_OBSTACLE_DISTANCE_CRC); -} - -/** - * @brief Pack a obstacle_distance message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @param sensor_type Class id of the distance sensor type. - * @param distances [cm] Distance of obstacles around the vehicle with index 0 corresponding to north + angle_offset, unless otherwise specified in the frame. A value of 0 is valid and means that the obstacle is practically touching the sensor. A value of max_distance +1 means no obstacle is present. A value of UINT16_MAX for unknown/not used. In a array element, one unit corresponds to 1cm. - * @param increment [deg] Angular width in degrees of each array element. Increment direction is clockwise. This field is ignored if increment_f is non-zero. - * @param min_distance [cm] Minimum distance the sensor can measure. - * @param max_distance [cm] Maximum distance the sensor can measure. - * @param increment_f [deg] Angular width in degrees of each array element as a float. If non-zero then this value is used instead of the uint8_t increment field. Positive is clockwise direction, negative is counter-clockwise. - * @param angle_offset [deg] Relative angle offset of the 0-index element in the distances array. Value of 0 corresponds to forward. Positive is clockwise direction, negative is counter-clockwise. - * @param frame Coordinate frame of reference for the yaw rotation and offset of the sensor data. Defaults to MAV_FRAME_GLOBAL, which is north aligned. For body-mounted sensors use MAV_FRAME_BODY_FRD, which is vehicle front aligned. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_obstacle_distance_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint64_t time_usec,uint8_t sensor_type,const uint16_t *distances,uint8_t increment,uint16_t min_distance,uint16_t max_distance,float increment_f,float angle_offset,uint8_t frame) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_OBSTACLE_DISTANCE_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint16_t(buf, 152, min_distance); - _mav_put_uint16_t(buf, 154, max_distance); - _mav_put_uint8_t(buf, 156, sensor_type); - _mav_put_uint8_t(buf, 157, increment); - _mav_put_float(buf, 158, increment_f); - _mav_put_float(buf, 162, angle_offset); - _mav_put_uint8_t(buf, 166, frame); - _mav_put_uint16_t_array(buf, 8, distances, 72); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OBSTACLE_DISTANCE_LEN); -#else - mavlink_obstacle_distance_t packet; - packet.time_usec = time_usec; - packet.min_distance = min_distance; - packet.max_distance = max_distance; - packet.sensor_type = sensor_type; - packet.increment = increment; - packet.increment_f = increment_f; - packet.angle_offset = angle_offset; - packet.frame = frame; - mav_array_memcpy(packet.distances, distances, sizeof(uint16_t)*72); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_OBSTACLE_DISTANCE_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_OBSTACLE_DISTANCE; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_OBSTACLE_DISTANCE_MIN_LEN, MAVLINK_MSG_ID_OBSTACLE_DISTANCE_LEN, MAVLINK_MSG_ID_OBSTACLE_DISTANCE_CRC); -} - -/** - * @brief Encode a obstacle_distance struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param obstacle_distance C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_obstacle_distance_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_obstacle_distance_t* obstacle_distance) -{ - return mavlink_msg_obstacle_distance_pack(system_id, component_id, msg, obstacle_distance->time_usec, obstacle_distance->sensor_type, obstacle_distance->distances, obstacle_distance->increment, obstacle_distance->min_distance, obstacle_distance->max_distance, obstacle_distance->increment_f, obstacle_distance->angle_offset, obstacle_distance->frame); -} - -/** - * @brief Encode a obstacle_distance struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param obstacle_distance C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_obstacle_distance_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_obstacle_distance_t* obstacle_distance) -{ - return mavlink_msg_obstacle_distance_pack_chan(system_id, component_id, chan, msg, obstacle_distance->time_usec, obstacle_distance->sensor_type, obstacle_distance->distances, obstacle_distance->increment, obstacle_distance->min_distance, obstacle_distance->max_distance, obstacle_distance->increment_f, obstacle_distance->angle_offset, obstacle_distance->frame); -} - -/** - * @brief Send a obstacle_distance message - * @param chan MAVLink channel to send the message - * - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @param sensor_type Class id of the distance sensor type. - * @param distances [cm] Distance of obstacles around the vehicle with index 0 corresponding to north + angle_offset, unless otherwise specified in the frame. A value of 0 is valid and means that the obstacle is practically touching the sensor. A value of max_distance +1 means no obstacle is present. A value of UINT16_MAX for unknown/not used. In a array element, one unit corresponds to 1cm. - * @param increment [deg] Angular width in degrees of each array element. Increment direction is clockwise. This field is ignored if increment_f is non-zero. - * @param min_distance [cm] Minimum distance the sensor can measure. - * @param max_distance [cm] Maximum distance the sensor can measure. - * @param increment_f [deg] Angular width in degrees of each array element as a float. If non-zero then this value is used instead of the uint8_t increment field. Positive is clockwise direction, negative is counter-clockwise. - * @param angle_offset [deg] Relative angle offset of the 0-index element in the distances array. Value of 0 corresponds to forward. Positive is clockwise direction, negative is counter-clockwise. - * @param frame Coordinate frame of reference for the yaw rotation and offset of the sensor data. Defaults to MAV_FRAME_GLOBAL, which is north aligned. For body-mounted sensors use MAV_FRAME_BODY_FRD, which is vehicle front aligned. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_obstacle_distance_send(mavlink_channel_t chan, uint64_t time_usec, uint8_t sensor_type, const uint16_t *distances, uint8_t increment, uint16_t min_distance, uint16_t max_distance, float increment_f, float angle_offset, uint8_t frame) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_OBSTACLE_DISTANCE_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint16_t(buf, 152, min_distance); - _mav_put_uint16_t(buf, 154, max_distance); - _mav_put_uint8_t(buf, 156, sensor_type); - _mav_put_uint8_t(buf, 157, increment); - _mav_put_float(buf, 158, increment_f); - _mav_put_float(buf, 162, angle_offset); - _mav_put_uint8_t(buf, 166, frame); - _mav_put_uint16_t_array(buf, 8, distances, 72); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBSTACLE_DISTANCE, buf, MAVLINK_MSG_ID_OBSTACLE_DISTANCE_MIN_LEN, MAVLINK_MSG_ID_OBSTACLE_DISTANCE_LEN, MAVLINK_MSG_ID_OBSTACLE_DISTANCE_CRC); -#else - mavlink_obstacle_distance_t packet; - packet.time_usec = time_usec; - packet.min_distance = min_distance; - packet.max_distance = max_distance; - packet.sensor_type = sensor_type; - packet.increment = increment; - packet.increment_f = increment_f; - packet.angle_offset = angle_offset; - packet.frame = frame; - mav_array_memcpy(packet.distances, distances, sizeof(uint16_t)*72); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBSTACLE_DISTANCE, (const char *)&packet, MAVLINK_MSG_ID_OBSTACLE_DISTANCE_MIN_LEN, MAVLINK_MSG_ID_OBSTACLE_DISTANCE_LEN, MAVLINK_MSG_ID_OBSTACLE_DISTANCE_CRC); -#endif -} - -/** - * @brief Send a obstacle_distance message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_obstacle_distance_send_struct(mavlink_channel_t chan, const mavlink_obstacle_distance_t* obstacle_distance) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_obstacle_distance_send(chan, obstacle_distance->time_usec, obstacle_distance->sensor_type, obstacle_distance->distances, obstacle_distance->increment, obstacle_distance->min_distance, obstacle_distance->max_distance, obstacle_distance->increment_f, obstacle_distance->angle_offset, obstacle_distance->frame); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBSTACLE_DISTANCE, (const char *)obstacle_distance, MAVLINK_MSG_ID_OBSTACLE_DISTANCE_MIN_LEN, MAVLINK_MSG_ID_OBSTACLE_DISTANCE_LEN, MAVLINK_MSG_ID_OBSTACLE_DISTANCE_CRC); -#endif -} - -#if MAVLINK_MSG_ID_OBSTACLE_DISTANCE_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_obstacle_distance_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, uint8_t sensor_type, const uint16_t *distances, uint8_t increment, uint16_t min_distance, uint16_t max_distance, float increment_f, float angle_offset, uint8_t frame) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint16_t(buf, 152, min_distance); - _mav_put_uint16_t(buf, 154, max_distance); - _mav_put_uint8_t(buf, 156, sensor_type); - _mav_put_uint8_t(buf, 157, increment); - _mav_put_float(buf, 158, increment_f); - _mav_put_float(buf, 162, angle_offset); - _mav_put_uint8_t(buf, 166, frame); - _mav_put_uint16_t_array(buf, 8, distances, 72); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBSTACLE_DISTANCE, buf, MAVLINK_MSG_ID_OBSTACLE_DISTANCE_MIN_LEN, MAVLINK_MSG_ID_OBSTACLE_DISTANCE_LEN, MAVLINK_MSG_ID_OBSTACLE_DISTANCE_CRC); -#else - mavlink_obstacle_distance_t *packet = (mavlink_obstacle_distance_t *)msgbuf; - packet->time_usec = time_usec; - packet->min_distance = min_distance; - packet->max_distance = max_distance; - packet->sensor_type = sensor_type; - packet->increment = increment; - packet->increment_f = increment_f; - packet->angle_offset = angle_offset; - packet->frame = frame; - mav_array_memcpy(packet->distances, distances, sizeof(uint16_t)*72); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBSTACLE_DISTANCE, (const char *)packet, MAVLINK_MSG_ID_OBSTACLE_DISTANCE_MIN_LEN, MAVLINK_MSG_ID_OBSTACLE_DISTANCE_LEN, MAVLINK_MSG_ID_OBSTACLE_DISTANCE_CRC); -#endif -} -#endif - -#endif - -// MESSAGE OBSTACLE_DISTANCE UNPACKING - - -/** - * @brief Get field time_usec from obstacle_distance message - * - * @return [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - */ -static inline uint64_t mavlink_msg_obstacle_distance_get_time_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field sensor_type from obstacle_distance message - * - * @return Class id of the distance sensor type. - */ -static inline uint8_t mavlink_msg_obstacle_distance_get_sensor_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 156); -} - -/** - * @brief Get field distances from obstacle_distance message - * - * @return [cm] Distance of obstacles around the vehicle with index 0 corresponding to north + angle_offset, unless otherwise specified in the frame. A value of 0 is valid and means that the obstacle is practically touching the sensor. A value of max_distance +1 means no obstacle is present. A value of UINT16_MAX for unknown/not used. In a array element, one unit corresponds to 1cm. - */ -static inline uint16_t mavlink_msg_obstacle_distance_get_distances(const mavlink_message_t* msg, uint16_t *distances) -{ - return _MAV_RETURN_uint16_t_array(msg, distances, 72, 8); -} - -/** - * @brief Get field increment from obstacle_distance message - * - * @return [deg] Angular width in degrees of each array element. Increment direction is clockwise. This field is ignored if increment_f is non-zero. - */ -static inline uint8_t mavlink_msg_obstacle_distance_get_increment(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 157); -} - -/** - * @brief Get field min_distance from obstacle_distance message - * - * @return [cm] Minimum distance the sensor can measure. - */ -static inline uint16_t mavlink_msg_obstacle_distance_get_min_distance(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 152); -} - -/** - * @brief Get field max_distance from obstacle_distance message - * - * @return [cm] Maximum distance the sensor can measure. - */ -static inline uint16_t mavlink_msg_obstacle_distance_get_max_distance(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 154); -} - -/** - * @brief Get field increment_f from obstacle_distance message - * - * @return [deg] Angular width in degrees of each array element as a float. If non-zero then this value is used instead of the uint8_t increment field. Positive is clockwise direction, negative is counter-clockwise. - */ -static inline float mavlink_msg_obstacle_distance_get_increment_f(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 158); -} - -/** - * @brief Get field angle_offset from obstacle_distance message - * - * @return [deg] Relative angle offset of the 0-index element in the distances array. Value of 0 corresponds to forward. Positive is clockwise direction, negative is counter-clockwise. - */ -static inline float mavlink_msg_obstacle_distance_get_angle_offset(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 162); -} - -/** - * @brief Get field frame from obstacle_distance message - * - * @return Coordinate frame of reference for the yaw rotation and offset of the sensor data. Defaults to MAV_FRAME_GLOBAL, which is north aligned. For body-mounted sensors use MAV_FRAME_BODY_FRD, which is vehicle front aligned. - */ -static inline uint8_t mavlink_msg_obstacle_distance_get_frame(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 166); -} - -/** - * @brief Decode a obstacle_distance message into a struct - * - * @param msg The message to decode - * @param obstacle_distance C-struct to decode the message contents into - */ -static inline void mavlink_msg_obstacle_distance_decode(const mavlink_message_t* msg, mavlink_obstacle_distance_t* obstacle_distance) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - obstacle_distance->time_usec = mavlink_msg_obstacle_distance_get_time_usec(msg); - mavlink_msg_obstacle_distance_get_distances(msg, obstacle_distance->distances); - obstacle_distance->min_distance = mavlink_msg_obstacle_distance_get_min_distance(msg); - obstacle_distance->max_distance = mavlink_msg_obstacle_distance_get_max_distance(msg); - obstacle_distance->sensor_type = mavlink_msg_obstacle_distance_get_sensor_type(msg); - obstacle_distance->increment = mavlink_msg_obstacle_distance_get_increment(msg); - obstacle_distance->increment_f = mavlink_msg_obstacle_distance_get_increment_f(msg); - obstacle_distance->angle_offset = mavlink_msg_obstacle_distance_get_angle_offset(msg); - obstacle_distance->frame = mavlink_msg_obstacle_distance_get_frame(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_OBSTACLE_DISTANCE_LEN? msg->len : MAVLINK_MSG_ID_OBSTACLE_DISTANCE_LEN; - memset(obstacle_distance, 0, MAVLINK_MSG_ID_OBSTACLE_DISTANCE_LEN); - memcpy(obstacle_distance, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_odometry.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_odometry.h deleted file mode 100644 index df2b74a6..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_odometry.h +++ /dev/null @@ -1,632 +0,0 @@ -#pragma once -// MESSAGE ODOMETRY PACKING - -#define MAVLINK_MSG_ID_ODOMETRY 331 - - -typedef struct __mavlink_odometry_t { - uint64_t time_usec; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/ - float x; /*< [m] X Position*/ - float y; /*< [m] Y Position*/ - float z; /*< [m] Z Position*/ - float q[4]; /*< Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation)*/ - float vx; /*< [m/s] X linear speed*/ - float vy; /*< [m/s] Y linear speed*/ - float vz; /*< [m/s] Z linear speed*/ - float rollspeed; /*< [rad/s] Roll angular speed*/ - float pitchspeed; /*< [rad/s] Pitch angular speed*/ - float yawspeed; /*< [rad/s] Yaw angular speed*/ - float pose_covariance[21]; /*< Row-major representation of a 6x6 pose cross-covariance matrix upper right triangle (states: x, y, z, roll, pitch, yaw; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array.*/ - float velocity_covariance[21]; /*< Row-major representation of a 6x6 velocity cross-covariance matrix upper right triangle (states: vx, vy, vz, rollspeed, pitchspeed, yawspeed; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array.*/ - uint8_t frame_id; /*< Coordinate frame of reference for the pose data.*/ - uint8_t child_frame_id; /*< Coordinate frame of reference for the velocity in free space (twist) data.*/ - uint8_t reset_counter; /*< Estimate reset counter. This should be incremented when the estimate resets in any of the dimensions (position, velocity, attitude, angular speed). This is designed to be used when e.g an external SLAM system detects a loop-closure and the estimate jumps.*/ - uint8_t estimator_type; /*< Type of estimator that is providing the odometry.*/ - int8_t quality; /*< [%] Optional odometry quality metric as a percentage. -1 = odometry has failed, 0 = unknown/unset quality, 1 = worst quality, 100 = best quality*/ -} mavlink_odometry_t; - -#define MAVLINK_MSG_ID_ODOMETRY_LEN 233 -#define MAVLINK_MSG_ID_ODOMETRY_MIN_LEN 230 -#define MAVLINK_MSG_ID_331_LEN 233 -#define MAVLINK_MSG_ID_331_MIN_LEN 230 - -#define MAVLINK_MSG_ID_ODOMETRY_CRC 91 -#define MAVLINK_MSG_ID_331_CRC 91 - -#define MAVLINK_MSG_ODOMETRY_FIELD_Q_LEN 4 -#define MAVLINK_MSG_ODOMETRY_FIELD_POSE_COVARIANCE_LEN 21 -#define MAVLINK_MSG_ODOMETRY_FIELD_VELOCITY_COVARIANCE_LEN 21 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_ODOMETRY { \ - 331, \ - "ODOMETRY", \ - 18, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_odometry_t, time_usec) }, \ - { "frame_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 228, offsetof(mavlink_odometry_t, frame_id) }, \ - { "child_frame_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 229, offsetof(mavlink_odometry_t, child_frame_id) }, \ - { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_odometry_t, x) }, \ - { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_odometry_t, y) }, \ - { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_odometry_t, z) }, \ - { "q", NULL, MAVLINK_TYPE_FLOAT, 4, 20, offsetof(mavlink_odometry_t, q) }, \ - { "vx", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_odometry_t, vx) }, \ - { "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_odometry_t, vy) }, \ - { "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_odometry_t, vz) }, \ - { "rollspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_odometry_t, rollspeed) }, \ - { "pitchspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_odometry_t, pitchspeed) }, \ - { "yawspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_odometry_t, yawspeed) }, \ - { "pose_covariance", NULL, MAVLINK_TYPE_FLOAT, 21, 60, offsetof(mavlink_odometry_t, pose_covariance) }, \ - { "velocity_covariance", NULL, MAVLINK_TYPE_FLOAT, 21, 144, offsetof(mavlink_odometry_t, velocity_covariance) }, \ - { "reset_counter", NULL, MAVLINK_TYPE_UINT8_T, 0, 230, offsetof(mavlink_odometry_t, reset_counter) }, \ - { "estimator_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 231, offsetof(mavlink_odometry_t, estimator_type) }, \ - { "quality", NULL, MAVLINK_TYPE_INT8_T, 0, 232, offsetof(mavlink_odometry_t, quality) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_ODOMETRY { \ - "ODOMETRY", \ - 18, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_odometry_t, time_usec) }, \ - { "frame_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 228, offsetof(mavlink_odometry_t, frame_id) }, \ - { "child_frame_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 229, offsetof(mavlink_odometry_t, child_frame_id) }, \ - { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_odometry_t, x) }, \ - { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_odometry_t, y) }, \ - { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_odometry_t, z) }, \ - { "q", NULL, MAVLINK_TYPE_FLOAT, 4, 20, offsetof(mavlink_odometry_t, q) }, \ - { "vx", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_odometry_t, vx) }, \ - { "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_odometry_t, vy) }, \ - { "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_odometry_t, vz) }, \ - { "rollspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_odometry_t, rollspeed) }, \ - { "pitchspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_odometry_t, pitchspeed) }, \ - { "yawspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_odometry_t, yawspeed) }, \ - { "pose_covariance", NULL, MAVLINK_TYPE_FLOAT, 21, 60, offsetof(mavlink_odometry_t, pose_covariance) }, \ - { "velocity_covariance", NULL, MAVLINK_TYPE_FLOAT, 21, 144, offsetof(mavlink_odometry_t, velocity_covariance) }, \ - { "reset_counter", NULL, MAVLINK_TYPE_UINT8_T, 0, 230, offsetof(mavlink_odometry_t, reset_counter) }, \ - { "estimator_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 231, offsetof(mavlink_odometry_t, estimator_type) }, \ - { "quality", NULL, MAVLINK_TYPE_INT8_T, 0, 232, offsetof(mavlink_odometry_t, quality) }, \ - } \ -} -#endif - -/** - * @brief Pack a odometry message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @param frame_id Coordinate frame of reference for the pose data. - * @param child_frame_id Coordinate frame of reference for the velocity in free space (twist) data. - * @param x [m] X Position - * @param y [m] Y Position - * @param z [m] Z Position - * @param q Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation) - * @param vx [m/s] X linear speed - * @param vy [m/s] Y linear speed - * @param vz [m/s] Z linear speed - * @param rollspeed [rad/s] Roll angular speed - * @param pitchspeed [rad/s] Pitch angular speed - * @param yawspeed [rad/s] Yaw angular speed - * @param pose_covariance Row-major representation of a 6x6 pose cross-covariance matrix upper right triangle (states: x, y, z, roll, pitch, yaw; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array. - * @param velocity_covariance Row-major representation of a 6x6 velocity cross-covariance matrix upper right triangle (states: vx, vy, vz, rollspeed, pitchspeed, yawspeed; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array. - * @param reset_counter Estimate reset counter. This should be incremented when the estimate resets in any of the dimensions (position, velocity, attitude, angular speed). This is designed to be used when e.g an external SLAM system detects a loop-closure and the estimate jumps. - * @param estimator_type Type of estimator that is providing the odometry. - * @param quality [%] Optional odometry quality metric as a percentage. -1 = odometry has failed, 0 = unknown/unset quality, 1 = worst quality, 100 = best quality - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_odometry_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint64_t time_usec, uint8_t frame_id, uint8_t child_frame_id, float x, float y, float z, const float *q, float vx, float vy, float vz, float rollspeed, float pitchspeed, float yawspeed, const float *pose_covariance, const float *velocity_covariance, uint8_t reset_counter, uint8_t estimator_type, int8_t quality) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_ODOMETRY_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, x); - _mav_put_float(buf, 12, y); - _mav_put_float(buf, 16, z); - _mav_put_float(buf, 36, vx); - _mav_put_float(buf, 40, vy); - _mav_put_float(buf, 44, vz); - _mav_put_float(buf, 48, rollspeed); - _mav_put_float(buf, 52, pitchspeed); - _mav_put_float(buf, 56, yawspeed); - _mav_put_uint8_t(buf, 228, frame_id); - _mav_put_uint8_t(buf, 229, child_frame_id); - _mav_put_uint8_t(buf, 230, reset_counter); - _mav_put_uint8_t(buf, 231, estimator_type); - _mav_put_int8_t(buf, 232, quality); - _mav_put_float_array(buf, 20, q, 4); - _mav_put_float_array(buf, 60, pose_covariance, 21); - _mav_put_float_array(buf, 144, velocity_covariance, 21); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ODOMETRY_LEN); -#else - mavlink_odometry_t packet; - packet.time_usec = time_usec; - packet.x = x; - packet.y = y; - packet.z = z; - packet.vx = vx; - packet.vy = vy; - packet.vz = vz; - packet.rollspeed = rollspeed; - packet.pitchspeed = pitchspeed; - packet.yawspeed = yawspeed; - packet.frame_id = frame_id; - packet.child_frame_id = child_frame_id; - packet.reset_counter = reset_counter; - packet.estimator_type = estimator_type; - packet.quality = quality; - mav_array_memcpy(packet.q, q, sizeof(float)*4); - mav_array_memcpy(packet.pose_covariance, pose_covariance, sizeof(float)*21); - mav_array_memcpy(packet.velocity_covariance, velocity_covariance, sizeof(float)*21); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ODOMETRY_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_ODOMETRY; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ODOMETRY_MIN_LEN, MAVLINK_MSG_ID_ODOMETRY_LEN, MAVLINK_MSG_ID_ODOMETRY_CRC); -} - -/** - * @brief Pack a odometry message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @param frame_id Coordinate frame of reference for the pose data. - * @param child_frame_id Coordinate frame of reference for the velocity in free space (twist) data. - * @param x [m] X Position - * @param y [m] Y Position - * @param z [m] Z Position - * @param q Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation) - * @param vx [m/s] X linear speed - * @param vy [m/s] Y linear speed - * @param vz [m/s] Z linear speed - * @param rollspeed [rad/s] Roll angular speed - * @param pitchspeed [rad/s] Pitch angular speed - * @param yawspeed [rad/s] Yaw angular speed - * @param pose_covariance Row-major representation of a 6x6 pose cross-covariance matrix upper right triangle (states: x, y, z, roll, pitch, yaw; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array. - * @param velocity_covariance Row-major representation of a 6x6 velocity cross-covariance matrix upper right triangle (states: vx, vy, vz, rollspeed, pitchspeed, yawspeed; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array. - * @param reset_counter Estimate reset counter. This should be incremented when the estimate resets in any of the dimensions (position, velocity, attitude, angular speed). This is designed to be used when e.g an external SLAM system detects a loop-closure and the estimate jumps. - * @param estimator_type Type of estimator that is providing the odometry. - * @param quality [%] Optional odometry quality metric as a percentage. -1 = odometry has failed, 0 = unknown/unset quality, 1 = worst quality, 100 = best quality - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_odometry_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint64_t time_usec,uint8_t frame_id,uint8_t child_frame_id,float x,float y,float z,const float *q,float vx,float vy,float vz,float rollspeed,float pitchspeed,float yawspeed,const float *pose_covariance,const float *velocity_covariance,uint8_t reset_counter,uint8_t estimator_type,int8_t quality) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_ODOMETRY_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, x); - _mav_put_float(buf, 12, y); - _mav_put_float(buf, 16, z); - _mav_put_float(buf, 36, vx); - _mav_put_float(buf, 40, vy); - _mav_put_float(buf, 44, vz); - _mav_put_float(buf, 48, rollspeed); - _mav_put_float(buf, 52, pitchspeed); - _mav_put_float(buf, 56, yawspeed); - _mav_put_uint8_t(buf, 228, frame_id); - _mav_put_uint8_t(buf, 229, child_frame_id); - _mav_put_uint8_t(buf, 230, reset_counter); - _mav_put_uint8_t(buf, 231, estimator_type); - _mav_put_int8_t(buf, 232, quality); - _mav_put_float_array(buf, 20, q, 4); - _mav_put_float_array(buf, 60, pose_covariance, 21); - _mav_put_float_array(buf, 144, velocity_covariance, 21); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ODOMETRY_LEN); -#else - mavlink_odometry_t packet; - packet.time_usec = time_usec; - packet.x = x; - packet.y = y; - packet.z = z; - packet.vx = vx; - packet.vy = vy; - packet.vz = vz; - packet.rollspeed = rollspeed; - packet.pitchspeed = pitchspeed; - packet.yawspeed = yawspeed; - packet.frame_id = frame_id; - packet.child_frame_id = child_frame_id; - packet.reset_counter = reset_counter; - packet.estimator_type = estimator_type; - packet.quality = quality; - mav_array_memcpy(packet.q, q, sizeof(float)*4); - mav_array_memcpy(packet.pose_covariance, pose_covariance, sizeof(float)*21); - mav_array_memcpy(packet.velocity_covariance, velocity_covariance, sizeof(float)*21); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ODOMETRY_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_ODOMETRY; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ODOMETRY_MIN_LEN, MAVLINK_MSG_ID_ODOMETRY_LEN, MAVLINK_MSG_ID_ODOMETRY_CRC); -} - -/** - * @brief Encode a odometry struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param odometry C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_odometry_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_odometry_t* odometry) -{ - return mavlink_msg_odometry_pack(system_id, component_id, msg, odometry->time_usec, odometry->frame_id, odometry->child_frame_id, odometry->x, odometry->y, odometry->z, odometry->q, odometry->vx, odometry->vy, odometry->vz, odometry->rollspeed, odometry->pitchspeed, odometry->yawspeed, odometry->pose_covariance, odometry->velocity_covariance, odometry->reset_counter, odometry->estimator_type, odometry->quality); -} - -/** - * @brief Encode a odometry struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param odometry C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_odometry_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_odometry_t* odometry) -{ - return mavlink_msg_odometry_pack_chan(system_id, component_id, chan, msg, odometry->time_usec, odometry->frame_id, odometry->child_frame_id, odometry->x, odometry->y, odometry->z, odometry->q, odometry->vx, odometry->vy, odometry->vz, odometry->rollspeed, odometry->pitchspeed, odometry->yawspeed, odometry->pose_covariance, odometry->velocity_covariance, odometry->reset_counter, odometry->estimator_type, odometry->quality); -} - -/** - * @brief Send a odometry message - * @param chan MAVLink channel to send the message - * - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @param frame_id Coordinate frame of reference for the pose data. - * @param child_frame_id Coordinate frame of reference for the velocity in free space (twist) data. - * @param x [m] X Position - * @param y [m] Y Position - * @param z [m] Z Position - * @param q Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation) - * @param vx [m/s] X linear speed - * @param vy [m/s] Y linear speed - * @param vz [m/s] Z linear speed - * @param rollspeed [rad/s] Roll angular speed - * @param pitchspeed [rad/s] Pitch angular speed - * @param yawspeed [rad/s] Yaw angular speed - * @param pose_covariance Row-major representation of a 6x6 pose cross-covariance matrix upper right triangle (states: x, y, z, roll, pitch, yaw; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array. - * @param velocity_covariance Row-major representation of a 6x6 velocity cross-covariance matrix upper right triangle (states: vx, vy, vz, rollspeed, pitchspeed, yawspeed; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array. - * @param reset_counter Estimate reset counter. This should be incremented when the estimate resets in any of the dimensions (position, velocity, attitude, angular speed). This is designed to be used when e.g an external SLAM system detects a loop-closure and the estimate jumps. - * @param estimator_type Type of estimator that is providing the odometry. - * @param quality [%] Optional odometry quality metric as a percentage. -1 = odometry has failed, 0 = unknown/unset quality, 1 = worst quality, 100 = best quality - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_odometry_send(mavlink_channel_t chan, uint64_t time_usec, uint8_t frame_id, uint8_t child_frame_id, float x, float y, float z, const float *q, float vx, float vy, float vz, float rollspeed, float pitchspeed, float yawspeed, const float *pose_covariance, const float *velocity_covariance, uint8_t reset_counter, uint8_t estimator_type, int8_t quality) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_ODOMETRY_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, x); - _mav_put_float(buf, 12, y); - _mav_put_float(buf, 16, z); - _mav_put_float(buf, 36, vx); - _mav_put_float(buf, 40, vy); - _mav_put_float(buf, 44, vz); - _mav_put_float(buf, 48, rollspeed); - _mav_put_float(buf, 52, pitchspeed); - _mav_put_float(buf, 56, yawspeed); - _mav_put_uint8_t(buf, 228, frame_id); - _mav_put_uint8_t(buf, 229, child_frame_id); - _mav_put_uint8_t(buf, 230, reset_counter); - _mav_put_uint8_t(buf, 231, estimator_type); - _mav_put_int8_t(buf, 232, quality); - _mav_put_float_array(buf, 20, q, 4); - _mav_put_float_array(buf, 60, pose_covariance, 21); - _mav_put_float_array(buf, 144, velocity_covariance, 21); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ODOMETRY, buf, MAVLINK_MSG_ID_ODOMETRY_MIN_LEN, MAVLINK_MSG_ID_ODOMETRY_LEN, MAVLINK_MSG_ID_ODOMETRY_CRC); -#else - mavlink_odometry_t packet; - packet.time_usec = time_usec; - packet.x = x; - packet.y = y; - packet.z = z; - packet.vx = vx; - packet.vy = vy; - packet.vz = vz; - packet.rollspeed = rollspeed; - packet.pitchspeed = pitchspeed; - packet.yawspeed = yawspeed; - packet.frame_id = frame_id; - packet.child_frame_id = child_frame_id; - packet.reset_counter = reset_counter; - packet.estimator_type = estimator_type; - packet.quality = quality; - mav_array_memcpy(packet.q, q, sizeof(float)*4); - mav_array_memcpy(packet.pose_covariance, pose_covariance, sizeof(float)*21); - mav_array_memcpy(packet.velocity_covariance, velocity_covariance, sizeof(float)*21); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ODOMETRY, (const char *)&packet, MAVLINK_MSG_ID_ODOMETRY_MIN_LEN, MAVLINK_MSG_ID_ODOMETRY_LEN, MAVLINK_MSG_ID_ODOMETRY_CRC); -#endif -} - -/** - * @brief Send a odometry message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_odometry_send_struct(mavlink_channel_t chan, const mavlink_odometry_t* odometry) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_odometry_send(chan, odometry->time_usec, odometry->frame_id, odometry->child_frame_id, odometry->x, odometry->y, odometry->z, odometry->q, odometry->vx, odometry->vy, odometry->vz, odometry->rollspeed, odometry->pitchspeed, odometry->yawspeed, odometry->pose_covariance, odometry->velocity_covariance, odometry->reset_counter, odometry->estimator_type, odometry->quality); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ODOMETRY, (const char *)odometry, MAVLINK_MSG_ID_ODOMETRY_MIN_LEN, MAVLINK_MSG_ID_ODOMETRY_LEN, MAVLINK_MSG_ID_ODOMETRY_CRC); -#endif -} - -#if MAVLINK_MSG_ID_ODOMETRY_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_odometry_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, uint8_t frame_id, uint8_t child_frame_id, float x, float y, float z, const float *q, float vx, float vy, float vz, float rollspeed, float pitchspeed, float yawspeed, const float *pose_covariance, const float *velocity_covariance, uint8_t reset_counter, uint8_t estimator_type, int8_t quality) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, x); - _mav_put_float(buf, 12, y); - _mav_put_float(buf, 16, z); - _mav_put_float(buf, 36, vx); - _mav_put_float(buf, 40, vy); - _mav_put_float(buf, 44, vz); - _mav_put_float(buf, 48, rollspeed); - _mav_put_float(buf, 52, pitchspeed); - _mav_put_float(buf, 56, yawspeed); - _mav_put_uint8_t(buf, 228, frame_id); - _mav_put_uint8_t(buf, 229, child_frame_id); - _mav_put_uint8_t(buf, 230, reset_counter); - _mav_put_uint8_t(buf, 231, estimator_type); - _mav_put_int8_t(buf, 232, quality); - _mav_put_float_array(buf, 20, q, 4); - _mav_put_float_array(buf, 60, pose_covariance, 21); - _mav_put_float_array(buf, 144, velocity_covariance, 21); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ODOMETRY, buf, MAVLINK_MSG_ID_ODOMETRY_MIN_LEN, MAVLINK_MSG_ID_ODOMETRY_LEN, MAVLINK_MSG_ID_ODOMETRY_CRC); -#else - mavlink_odometry_t *packet = (mavlink_odometry_t *)msgbuf; - packet->time_usec = time_usec; - packet->x = x; - packet->y = y; - packet->z = z; - packet->vx = vx; - packet->vy = vy; - packet->vz = vz; - packet->rollspeed = rollspeed; - packet->pitchspeed = pitchspeed; - packet->yawspeed = yawspeed; - packet->frame_id = frame_id; - packet->child_frame_id = child_frame_id; - packet->reset_counter = reset_counter; - packet->estimator_type = estimator_type; - packet->quality = quality; - mav_array_memcpy(packet->q, q, sizeof(float)*4); - mav_array_memcpy(packet->pose_covariance, pose_covariance, sizeof(float)*21); - mav_array_memcpy(packet->velocity_covariance, velocity_covariance, sizeof(float)*21); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ODOMETRY, (const char *)packet, MAVLINK_MSG_ID_ODOMETRY_MIN_LEN, MAVLINK_MSG_ID_ODOMETRY_LEN, MAVLINK_MSG_ID_ODOMETRY_CRC); -#endif -} -#endif - -#endif - -// MESSAGE ODOMETRY UNPACKING - - -/** - * @brief Get field time_usec from odometry message - * - * @return [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - */ -static inline uint64_t mavlink_msg_odometry_get_time_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field frame_id from odometry message - * - * @return Coordinate frame of reference for the pose data. - */ -static inline uint8_t mavlink_msg_odometry_get_frame_id(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 228); -} - -/** - * @brief Get field child_frame_id from odometry message - * - * @return Coordinate frame of reference for the velocity in free space (twist) data. - */ -static inline uint8_t mavlink_msg_odometry_get_child_frame_id(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 229); -} - -/** - * @brief Get field x from odometry message - * - * @return [m] X Position - */ -static inline float mavlink_msg_odometry_get_x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field y from odometry message - * - * @return [m] Y Position - */ -static inline float mavlink_msg_odometry_get_y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field z from odometry message - * - * @return [m] Z Position - */ -static inline float mavlink_msg_odometry_get_z(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field q from odometry message - * - * @return Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation) - */ -static inline uint16_t mavlink_msg_odometry_get_q(const mavlink_message_t* msg, float *q) -{ - return _MAV_RETURN_float_array(msg, q, 4, 20); -} - -/** - * @brief Get field vx from odometry message - * - * @return [m/s] X linear speed - */ -static inline float mavlink_msg_odometry_get_vx(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 36); -} - -/** - * @brief Get field vy from odometry message - * - * @return [m/s] Y linear speed - */ -static inline float mavlink_msg_odometry_get_vy(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 40); -} - -/** - * @brief Get field vz from odometry message - * - * @return [m/s] Z linear speed - */ -static inline float mavlink_msg_odometry_get_vz(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 44); -} - -/** - * @brief Get field rollspeed from odometry message - * - * @return [rad/s] Roll angular speed - */ -static inline float mavlink_msg_odometry_get_rollspeed(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 48); -} - -/** - * @brief Get field pitchspeed from odometry message - * - * @return [rad/s] Pitch angular speed - */ -static inline float mavlink_msg_odometry_get_pitchspeed(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 52); -} - -/** - * @brief Get field yawspeed from odometry message - * - * @return [rad/s] Yaw angular speed - */ -static inline float mavlink_msg_odometry_get_yawspeed(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 56); -} - -/** - * @brief Get field pose_covariance from odometry message - * - * @return Row-major representation of a 6x6 pose cross-covariance matrix upper right triangle (states: x, y, z, roll, pitch, yaw; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array. - */ -static inline uint16_t mavlink_msg_odometry_get_pose_covariance(const mavlink_message_t* msg, float *pose_covariance) -{ - return _MAV_RETURN_float_array(msg, pose_covariance, 21, 60); -} - -/** - * @brief Get field velocity_covariance from odometry message - * - * @return Row-major representation of a 6x6 velocity cross-covariance matrix upper right triangle (states: vx, vy, vz, rollspeed, pitchspeed, yawspeed; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array. - */ -static inline uint16_t mavlink_msg_odometry_get_velocity_covariance(const mavlink_message_t* msg, float *velocity_covariance) -{ - return _MAV_RETURN_float_array(msg, velocity_covariance, 21, 144); -} - -/** - * @brief Get field reset_counter from odometry message - * - * @return Estimate reset counter. This should be incremented when the estimate resets in any of the dimensions (position, velocity, attitude, angular speed). This is designed to be used when e.g an external SLAM system detects a loop-closure and the estimate jumps. - */ -static inline uint8_t mavlink_msg_odometry_get_reset_counter(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 230); -} - -/** - * @brief Get field estimator_type from odometry message - * - * @return Type of estimator that is providing the odometry. - */ -static inline uint8_t mavlink_msg_odometry_get_estimator_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 231); -} - -/** - * @brief Get field quality from odometry message - * - * @return [%] Optional odometry quality metric as a percentage. -1 = odometry has failed, 0 = unknown/unset quality, 1 = worst quality, 100 = best quality - */ -static inline int8_t mavlink_msg_odometry_get_quality(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int8_t(msg, 232); -} - -/** - * @brief Decode a odometry message into a struct - * - * @param msg The message to decode - * @param odometry C-struct to decode the message contents into - */ -static inline void mavlink_msg_odometry_decode(const mavlink_message_t* msg, mavlink_odometry_t* odometry) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - odometry->time_usec = mavlink_msg_odometry_get_time_usec(msg); - odometry->x = mavlink_msg_odometry_get_x(msg); - odometry->y = mavlink_msg_odometry_get_y(msg); - odometry->z = mavlink_msg_odometry_get_z(msg); - mavlink_msg_odometry_get_q(msg, odometry->q); - odometry->vx = mavlink_msg_odometry_get_vx(msg); - odometry->vy = mavlink_msg_odometry_get_vy(msg); - odometry->vz = mavlink_msg_odometry_get_vz(msg); - odometry->rollspeed = mavlink_msg_odometry_get_rollspeed(msg); - odometry->pitchspeed = mavlink_msg_odometry_get_pitchspeed(msg); - odometry->yawspeed = mavlink_msg_odometry_get_yawspeed(msg); - mavlink_msg_odometry_get_pose_covariance(msg, odometry->pose_covariance); - mavlink_msg_odometry_get_velocity_covariance(msg, odometry->velocity_covariance); - odometry->frame_id = mavlink_msg_odometry_get_frame_id(msg); - odometry->child_frame_id = mavlink_msg_odometry_get_child_frame_id(msg); - odometry->reset_counter = mavlink_msg_odometry_get_reset_counter(msg); - odometry->estimator_type = mavlink_msg_odometry_get_estimator_type(msg); - odometry->quality = mavlink_msg_odometry_get_quality(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_ODOMETRY_LEN? msg->len : MAVLINK_MSG_ID_ODOMETRY_LEN; - memset(odometry, 0, MAVLINK_MSG_ID_ODOMETRY_LEN); - memcpy(odometry, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_onboard_computer_status.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_onboard_computer_status.h deleted file mode 100644 index 55bb396f..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_onboard_computer_status.h +++ /dev/null @@ -1,693 +0,0 @@ -#pragma once -// MESSAGE ONBOARD_COMPUTER_STATUS PACKING - -#define MAVLINK_MSG_ID_ONBOARD_COMPUTER_STATUS 390 - - -typedef struct __mavlink_onboard_computer_status_t { - uint64_t time_usec; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/ - uint32_t uptime; /*< [ms] Time since system boot.*/ - uint32_t ram_usage; /*< [MiB] Amount of used RAM on the component system. A value of UINT32_MAX implies the field is unused.*/ - uint32_t ram_total; /*< [MiB] Total amount of RAM on the component system. A value of UINT32_MAX implies the field is unused.*/ - uint32_t storage_type[4]; /*< Storage type: 0: HDD, 1: SSD, 2: EMMC, 3: SD card (non-removable), 4: SD card (removable). A value of UINT32_MAX implies the field is unused.*/ - uint32_t storage_usage[4]; /*< [MiB] Amount of used storage space on the component system. A value of UINT32_MAX implies the field is unused.*/ - uint32_t storage_total[4]; /*< [MiB] Total amount of storage space on the component system. A value of UINT32_MAX implies the field is unused.*/ - uint32_t link_type[6]; /*< Link type: 0-9: UART, 10-19: Wired network, 20-29: Wifi, 30-39: Point-to-point proprietary, 40-49: Mesh proprietary*/ - uint32_t link_tx_rate[6]; /*< [KiB/s] Network traffic from the component system. A value of UINT32_MAX implies the field is unused.*/ - uint32_t link_rx_rate[6]; /*< [KiB/s] Network traffic to the component system. A value of UINT32_MAX implies the field is unused.*/ - uint32_t link_tx_max[6]; /*< [KiB/s] Network capacity from the component system. A value of UINT32_MAX implies the field is unused.*/ - uint32_t link_rx_max[6]; /*< [KiB/s] Network capacity to the component system. A value of UINT32_MAX implies the field is unused.*/ - int16_t fan_speed[4]; /*< [rpm] Fan speeds. A value of INT16_MAX implies the field is unused.*/ - uint8_t type; /*< Type of the onboard computer: 0: Mission computer primary, 1: Mission computer backup 1, 2: Mission computer backup 2, 3: Compute node, 4-5: Compute spares, 6-9: Payload computers.*/ - uint8_t cpu_cores[8]; /*< CPU usage on the component in percent (100 - idle). A value of UINT8_MAX implies the field is unused.*/ - uint8_t cpu_combined[10]; /*< Combined CPU usage as the last 10 slices of 100 MS (a histogram). This allows to identify spikes in load that max out the system, but only for a short amount of time. A value of UINT8_MAX implies the field is unused.*/ - uint8_t gpu_cores[4]; /*< GPU usage on the component in percent (100 - idle). A value of UINT8_MAX implies the field is unused.*/ - uint8_t gpu_combined[10]; /*< Combined GPU usage as the last 10 slices of 100 MS (a histogram). This allows to identify spikes in load that max out the system, but only for a short amount of time. A value of UINT8_MAX implies the field is unused.*/ - int8_t temperature_board; /*< [degC] Temperature of the board. A value of INT8_MAX implies the field is unused.*/ - int8_t temperature_core[8]; /*< [degC] Temperature of the CPU core. A value of INT8_MAX implies the field is unused.*/ -} mavlink_onboard_computer_status_t; - -#define MAVLINK_MSG_ID_ONBOARD_COMPUTER_STATUS_LEN 238 -#define MAVLINK_MSG_ID_ONBOARD_COMPUTER_STATUS_MIN_LEN 238 -#define MAVLINK_MSG_ID_390_LEN 238 -#define MAVLINK_MSG_ID_390_MIN_LEN 238 - -#define MAVLINK_MSG_ID_ONBOARD_COMPUTER_STATUS_CRC 156 -#define MAVLINK_MSG_ID_390_CRC 156 - -#define MAVLINK_MSG_ONBOARD_COMPUTER_STATUS_FIELD_STORAGE_TYPE_LEN 4 -#define MAVLINK_MSG_ONBOARD_COMPUTER_STATUS_FIELD_STORAGE_USAGE_LEN 4 -#define MAVLINK_MSG_ONBOARD_COMPUTER_STATUS_FIELD_STORAGE_TOTAL_LEN 4 -#define MAVLINK_MSG_ONBOARD_COMPUTER_STATUS_FIELD_LINK_TYPE_LEN 6 -#define MAVLINK_MSG_ONBOARD_COMPUTER_STATUS_FIELD_LINK_TX_RATE_LEN 6 -#define MAVLINK_MSG_ONBOARD_COMPUTER_STATUS_FIELD_LINK_RX_RATE_LEN 6 -#define MAVLINK_MSG_ONBOARD_COMPUTER_STATUS_FIELD_LINK_TX_MAX_LEN 6 -#define MAVLINK_MSG_ONBOARD_COMPUTER_STATUS_FIELD_LINK_RX_MAX_LEN 6 -#define MAVLINK_MSG_ONBOARD_COMPUTER_STATUS_FIELD_FAN_SPEED_LEN 4 -#define MAVLINK_MSG_ONBOARD_COMPUTER_STATUS_FIELD_CPU_CORES_LEN 8 -#define MAVLINK_MSG_ONBOARD_COMPUTER_STATUS_FIELD_CPU_COMBINED_LEN 10 -#define MAVLINK_MSG_ONBOARD_COMPUTER_STATUS_FIELD_GPU_CORES_LEN 4 -#define MAVLINK_MSG_ONBOARD_COMPUTER_STATUS_FIELD_GPU_COMBINED_LEN 10 -#define MAVLINK_MSG_ONBOARD_COMPUTER_STATUS_FIELD_TEMPERATURE_CORE_LEN 8 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_ONBOARD_COMPUTER_STATUS { \ - 390, \ - "ONBOARD_COMPUTER_STATUS", \ - 20, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_onboard_computer_status_t, time_usec) }, \ - { "uptime", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_onboard_computer_status_t, uptime) }, \ - { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 196, offsetof(mavlink_onboard_computer_status_t, type) }, \ - { "cpu_cores", NULL, MAVLINK_TYPE_UINT8_T, 8, 197, offsetof(mavlink_onboard_computer_status_t, cpu_cores) }, \ - { "cpu_combined", NULL, MAVLINK_TYPE_UINT8_T, 10, 205, offsetof(mavlink_onboard_computer_status_t, cpu_combined) }, \ - { "gpu_cores", NULL, MAVLINK_TYPE_UINT8_T, 4, 215, offsetof(mavlink_onboard_computer_status_t, gpu_cores) }, \ - { "gpu_combined", NULL, MAVLINK_TYPE_UINT8_T, 10, 219, offsetof(mavlink_onboard_computer_status_t, gpu_combined) }, \ - { "temperature_board", NULL, MAVLINK_TYPE_INT8_T, 0, 229, offsetof(mavlink_onboard_computer_status_t, temperature_board) }, \ - { "temperature_core", NULL, MAVLINK_TYPE_INT8_T, 8, 230, offsetof(mavlink_onboard_computer_status_t, temperature_core) }, \ - { "fan_speed", NULL, MAVLINK_TYPE_INT16_T, 4, 188, offsetof(mavlink_onboard_computer_status_t, fan_speed) }, \ - { "ram_usage", NULL, MAVLINK_TYPE_UINT32_T, 0, 12, offsetof(mavlink_onboard_computer_status_t, ram_usage) }, \ - { "ram_total", NULL, MAVLINK_TYPE_UINT32_T, 0, 16, offsetof(mavlink_onboard_computer_status_t, ram_total) }, \ - { "storage_type", NULL, MAVLINK_TYPE_UINT32_T, 4, 20, offsetof(mavlink_onboard_computer_status_t, storage_type) }, \ - { "storage_usage", NULL, MAVLINK_TYPE_UINT32_T, 4, 36, offsetof(mavlink_onboard_computer_status_t, storage_usage) }, \ - { "storage_total", NULL, MAVLINK_TYPE_UINT32_T, 4, 52, offsetof(mavlink_onboard_computer_status_t, storage_total) }, \ - { "link_type", NULL, MAVLINK_TYPE_UINT32_T, 6, 68, offsetof(mavlink_onboard_computer_status_t, link_type) }, \ - { "link_tx_rate", NULL, MAVLINK_TYPE_UINT32_T, 6, 92, offsetof(mavlink_onboard_computer_status_t, link_tx_rate) }, \ - { "link_rx_rate", NULL, MAVLINK_TYPE_UINT32_T, 6, 116, offsetof(mavlink_onboard_computer_status_t, link_rx_rate) }, \ - { "link_tx_max", NULL, MAVLINK_TYPE_UINT32_T, 6, 140, offsetof(mavlink_onboard_computer_status_t, link_tx_max) }, \ - { "link_rx_max", NULL, MAVLINK_TYPE_UINT32_T, 6, 164, offsetof(mavlink_onboard_computer_status_t, link_rx_max) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_ONBOARD_COMPUTER_STATUS { \ - "ONBOARD_COMPUTER_STATUS", \ - 20, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_onboard_computer_status_t, time_usec) }, \ - { "uptime", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_onboard_computer_status_t, uptime) }, \ - { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 196, offsetof(mavlink_onboard_computer_status_t, type) }, \ - { "cpu_cores", NULL, MAVLINK_TYPE_UINT8_T, 8, 197, offsetof(mavlink_onboard_computer_status_t, cpu_cores) }, \ - { "cpu_combined", NULL, MAVLINK_TYPE_UINT8_T, 10, 205, offsetof(mavlink_onboard_computer_status_t, cpu_combined) }, \ - { "gpu_cores", NULL, MAVLINK_TYPE_UINT8_T, 4, 215, offsetof(mavlink_onboard_computer_status_t, gpu_cores) }, \ - { "gpu_combined", NULL, MAVLINK_TYPE_UINT8_T, 10, 219, offsetof(mavlink_onboard_computer_status_t, gpu_combined) }, \ - { "temperature_board", NULL, MAVLINK_TYPE_INT8_T, 0, 229, offsetof(mavlink_onboard_computer_status_t, temperature_board) }, \ - { "temperature_core", NULL, MAVLINK_TYPE_INT8_T, 8, 230, offsetof(mavlink_onboard_computer_status_t, temperature_core) }, \ - { "fan_speed", NULL, MAVLINK_TYPE_INT16_T, 4, 188, offsetof(mavlink_onboard_computer_status_t, fan_speed) }, \ - { "ram_usage", NULL, MAVLINK_TYPE_UINT32_T, 0, 12, offsetof(mavlink_onboard_computer_status_t, ram_usage) }, \ - { "ram_total", NULL, MAVLINK_TYPE_UINT32_T, 0, 16, offsetof(mavlink_onboard_computer_status_t, ram_total) }, \ - { "storage_type", NULL, MAVLINK_TYPE_UINT32_T, 4, 20, offsetof(mavlink_onboard_computer_status_t, storage_type) }, \ - { "storage_usage", NULL, MAVLINK_TYPE_UINT32_T, 4, 36, offsetof(mavlink_onboard_computer_status_t, storage_usage) }, \ - { "storage_total", NULL, MAVLINK_TYPE_UINT32_T, 4, 52, offsetof(mavlink_onboard_computer_status_t, storage_total) }, \ - { "link_type", NULL, MAVLINK_TYPE_UINT32_T, 6, 68, offsetof(mavlink_onboard_computer_status_t, link_type) }, \ - { "link_tx_rate", NULL, MAVLINK_TYPE_UINT32_T, 6, 92, offsetof(mavlink_onboard_computer_status_t, link_tx_rate) }, \ - { "link_rx_rate", NULL, MAVLINK_TYPE_UINT32_T, 6, 116, offsetof(mavlink_onboard_computer_status_t, link_rx_rate) }, \ - { "link_tx_max", NULL, MAVLINK_TYPE_UINT32_T, 6, 140, offsetof(mavlink_onboard_computer_status_t, link_tx_max) }, \ - { "link_rx_max", NULL, MAVLINK_TYPE_UINT32_T, 6, 164, offsetof(mavlink_onboard_computer_status_t, link_rx_max) }, \ - } \ -} -#endif - -/** - * @brief Pack a onboard_computer_status message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @param uptime [ms] Time since system boot. - * @param type Type of the onboard computer: 0: Mission computer primary, 1: Mission computer backup 1, 2: Mission computer backup 2, 3: Compute node, 4-5: Compute spares, 6-9: Payload computers. - * @param cpu_cores CPU usage on the component in percent (100 - idle). A value of UINT8_MAX implies the field is unused. - * @param cpu_combined Combined CPU usage as the last 10 slices of 100 MS (a histogram). This allows to identify spikes in load that max out the system, but only for a short amount of time. A value of UINT8_MAX implies the field is unused. - * @param gpu_cores GPU usage on the component in percent (100 - idle). A value of UINT8_MAX implies the field is unused. - * @param gpu_combined Combined GPU usage as the last 10 slices of 100 MS (a histogram). This allows to identify spikes in load that max out the system, but only for a short amount of time. A value of UINT8_MAX implies the field is unused. - * @param temperature_board [degC] Temperature of the board. A value of INT8_MAX implies the field is unused. - * @param temperature_core [degC] Temperature of the CPU core. A value of INT8_MAX implies the field is unused. - * @param fan_speed [rpm] Fan speeds. A value of INT16_MAX implies the field is unused. - * @param ram_usage [MiB] Amount of used RAM on the component system. A value of UINT32_MAX implies the field is unused. - * @param ram_total [MiB] Total amount of RAM on the component system. A value of UINT32_MAX implies the field is unused. - * @param storage_type Storage type: 0: HDD, 1: SSD, 2: EMMC, 3: SD card (non-removable), 4: SD card (removable). A value of UINT32_MAX implies the field is unused. - * @param storage_usage [MiB] Amount of used storage space on the component system. A value of UINT32_MAX implies the field is unused. - * @param storage_total [MiB] Total amount of storage space on the component system. A value of UINT32_MAX implies the field is unused. - * @param link_type Link type: 0-9: UART, 10-19: Wired network, 20-29: Wifi, 30-39: Point-to-point proprietary, 40-49: Mesh proprietary - * @param link_tx_rate [KiB/s] Network traffic from the component system. A value of UINT32_MAX implies the field is unused. - * @param link_rx_rate [KiB/s] Network traffic to the component system. A value of UINT32_MAX implies the field is unused. - * @param link_tx_max [KiB/s] Network capacity from the component system. A value of UINT32_MAX implies the field is unused. - * @param link_rx_max [KiB/s] Network capacity to the component system. A value of UINT32_MAX implies the field is unused. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_onboard_computer_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint64_t time_usec, uint32_t uptime, uint8_t type, const uint8_t *cpu_cores, const uint8_t *cpu_combined, const uint8_t *gpu_cores, const uint8_t *gpu_combined, int8_t temperature_board, const int8_t *temperature_core, const int16_t *fan_speed, uint32_t ram_usage, uint32_t ram_total, const uint32_t *storage_type, const uint32_t *storage_usage, const uint32_t *storage_total, const uint32_t *link_type, const uint32_t *link_tx_rate, const uint32_t *link_rx_rate, const uint32_t *link_tx_max, const uint32_t *link_rx_max) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_ONBOARD_COMPUTER_STATUS_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint32_t(buf, 8, uptime); - _mav_put_uint32_t(buf, 12, ram_usage); - _mav_put_uint32_t(buf, 16, ram_total); - _mav_put_uint8_t(buf, 196, type); - _mav_put_int8_t(buf, 229, temperature_board); - _mav_put_uint32_t_array(buf, 20, storage_type, 4); - _mav_put_uint32_t_array(buf, 36, storage_usage, 4); - _mav_put_uint32_t_array(buf, 52, storage_total, 4); - _mav_put_uint32_t_array(buf, 68, link_type, 6); - _mav_put_uint32_t_array(buf, 92, link_tx_rate, 6); - _mav_put_uint32_t_array(buf, 116, link_rx_rate, 6); - _mav_put_uint32_t_array(buf, 140, link_tx_max, 6); - _mav_put_uint32_t_array(buf, 164, link_rx_max, 6); - _mav_put_int16_t_array(buf, 188, fan_speed, 4); - _mav_put_uint8_t_array(buf, 197, cpu_cores, 8); - _mav_put_uint8_t_array(buf, 205, cpu_combined, 10); - _mav_put_uint8_t_array(buf, 215, gpu_cores, 4); - _mav_put_uint8_t_array(buf, 219, gpu_combined, 10); - _mav_put_int8_t_array(buf, 230, temperature_core, 8); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ONBOARD_COMPUTER_STATUS_LEN); -#else - mavlink_onboard_computer_status_t packet; - packet.time_usec = time_usec; - packet.uptime = uptime; - packet.ram_usage = ram_usage; - packet.ram_total = ram_total; - packet.type = type; - packet.temperature_board = temperature_board; - mav_array_memcpy(packet.storage_type, storage_type, sizeof(uint32_t)*4); - mav_array_memcpy(packet.storage_usage, storage_usage, sizeof(uint32_t)*4); - mav_array_memcpy(packet.storage_total, storage_total, sizeof(uint32_t)*4); - mav_array_memcpy(packet.link_type, link_type, sizeof(uint32_t)*6); - mav_array_memcpy(packet.link_tx_rate, link_tx_rate, sizeof(uint32_t)*6); - mav_array_memcpy(packet.link_rx_rate, link_rx_rate, sizeof(uint32_t)*6); - mav_array_memcpy(packet.link_tx_max, link_tx_max, sizeof(uint32_t)*6); - mav_array_memcpy(packet.link_rx_max, link_rx_max, sizeof(uint32_t)*6); - mav_array_memcpy(packet.fan_speed, fan_speed, sizeof(int16_t)*4); - mav_array_memcpy(packet.cpu_cores, cpu_cores, sizeof(uint8_t)*8); - mav_array_memcpy(packet.cpu_combined, cpu_combined, sizeof(uint8_t)*10); - mav_array_memcpy(packet.gpu_cores, gpu_cores, sizeof(uint8_t)*4); - mav_array_memcpy(packet.gpu_combined, gpu_combined, sizeof(uint8_t)*10); - mav_array_memcpy(packet.temperature_core, temperature_core, sizeof(int8_t)*8); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ONBOARD_COMPUTER_STATUS_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_ONBOARD_COMPUTER_STATUS; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ONBOARD_COMPUTER_STATUS_MIN_LEN, MAVLINK_MSG_ID_ONBOARD_COMPUTER_STATUS_LEN, MAVLINK_MSG_ID_ONBOARD_COMPUTER_STATUS_CRC); -} - -/** - * @brief Pack a onboard_computer_status message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @param uptime [ms] Time since system boot. - * @param type Type of the onboard computer: 0: Mission computer primary, 1: Mission computer backup 1, 2: Mission computer backup 2, 3: Compute node, 4-5: Compute spares, 6-9: Payload computers. - * @param cpu_cores CPU usage on the component in percent (100 - idle). A value of UINT8_MAX implies the field is unused. - * @param cpu_combined Combined CPU usage as the last 10 slices of 100 MS (a histogram). This allows to identify spikes in load that max out the system, but only for a short amount of time. A value of UINT8_MAX implies the field is unused. - * @param gpu_cores GPU usage on the component in percent (100 - idle). A value of UINT8_MAX implies the field is unused. - * @param gpu_combined Combined GPU usage as the last 10 slices of 100 MS (a histogram). This allows to identify spikes in load that max out the system, but only for a short amount of time. A value of UINT8_MAX implies the field is unused. - * @param temperature_board [degC] Temperature of the board. A value of INT8_MAX implies the field is unused. - * @param temperature_core [degC] Temperature of the CPU core. A value of INT8_MAX implies the field is unused. - * @param fan_speed [rpm] Fan speeds. A value of INT16_MAX implies the field is unused. - * @param ram_usage [MiB] Amount of used RAM on the component system. A value of UINT32_MAX implies the field is unused. - * @param ram_total [MiB] Total amount of RAM on the component system. A value of UINT32_MAX implies the field is unused. - * @param storage_type Storage type: 0: HDD, 1: SSD, 2: EMMC, 3: SD card (non-removable), 4: SD card (removable). A value of UINT32_MAX implies the field is unused. - * @param storage_usage [MiB] Amount of used storage space on the component system. A value of UINT32_MAX implies the field is unused. - * @param storage_total [MiB] Total amount of storage space on the component system. A value of UINT32_MAX implies the field is unused. - * @param link_type Link type: 0-9: UART, 10-19: Wired network, 20-29: Wifi, 30-39: Point-to-point proprietary, 40-49: Mesh proprietary - * @param link_tx_rate [KiB/s] Network traffic from the component system. A value of UINT32_MAX implies the field is unused. - * @param link_rx_rate [KiB/s] Network traffic to the component system. A value of UINT32_MAX implies the field is unused. - * @param link_tx_max [KiB/s] Network capacity from the component system. A value of UINT32_MAX implies the field is unused. - * @param link_rx_max [KiB/s] Network capacity to the component system. A value of UINT32_MAX implies the field is unused. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_onboard_computer_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint64_t time_usec,uint32_t uptime,uint8_t type,const uint8_t *cpu_cores,const uint8_t *cpu_combined,const uint8_t *gpu_cores,const uint8_t *gpu_combined,int8_t temperature_board,const int8_t *temperature_core,const int16_t *fan_speed,uint32_t ram_usage,uint32_t ram_total,const uint32_t *storage_type,const uint32_t *storage_usage,const uint32_t *storage_total,const uint32_t *link_type,const uint32_t *link_tx_rate,const uint32_t *link_rx_rate,const uint32_t *link_tx_max,const uint32_t *link_rx_max) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_ONBOARD_COMPUTER_STATUS_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint32_t(buf, 8, uptime); - _mav_put_uint32_t(buf, 12, ram_usage); - _mav_put_uint32_t(buf, 16, ram_total); - _mav_put_uint8_t(buf, 196, type); - _mav_put_int8_t(buf, 229, temperature_board); - _mav_put_uint32_t_array(buf, 20, storage_type, 4); - _mav_put_uint32_t_array(buf, 36, storage_usage, 4); - _mav_put_uint32_t_array(buf, 52, storage_total, 4); - _mav_put_uint32_t_array(buf, 68, link_type, 6); - _mav_put_uint32_t_array(buf, 92, link_tx_rate, 6); - _mav_put_uint32_t_array(buf, 116, link_rx_rate, 6); - _mav_put_uint32_t_array(buf, 140, link_tx_max, 6); - _mav_put_uint32_t_array(buf, 164, link_rx_max, 6); - _mav_put_int16_t_array(buf, 188, fan_speed, 4); - _mav_put_uint8_t_array(buf, 197, cpu_cores, 8); - _mav_put_uint8_t_array(buf, 205, cpu_combined, 10); - _mav_put_uint8_t_array(buf, 215, gpu_cores, 4); - _mav_put_uint8_t_array(buf, 219, gpu_combined, 10); - _mav_put_int8_t_array(buf, 230, temperature_core, 8); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ONBOARD_COMPUTER_STATUS_LEN); -#else - mavlink_onboard_computer_status_t packet; - packet.time_usec = time_usec; - packet.uptime = uptime; - packet.ram_usage = ram_usage; - packet.ram_total = ram_total; - packet.type = type; - packet.temperature_board = temperature_board; - mav_array_memcpy(packet.storage_type, storage_type, sizeof(uint32_t)*4); - mav_array_memcpy(packet.storage_usage, storage_usage, sizeof(uint32_t)*4); - mav_array_memcpy(packet.storage_total, storage_total, sizeof(uint32_t)*4); - mav_array_memcpy(packet.link_type, link_type, sizeof(uint32_t)*6); - mav_array_memcpy(packet.link_tx_rate, link_tx_rate, sizeof(uint32_t)*6); - mav_array_memcpy(packet.link_rx_rate, link_rx_rate, sizeof(uint32_t)*6); - mav_array_memcpy(packet.link_tx_max, link_tx_max, sizeof(uint32_t)*6); - mav_array_memcpy(packet.link_rx_max, link_rx_max, sizeof(uint32_t)*6); - mav_array_memcpy(packet.fan_speed, fan_speed, sizeof(int16_t)*4); - mav_array_memcpy(packet.cpu_cores, cpu_cores, sizeof(uint8_t)*8); - mav_array_memcpy(packet.cpu_combined, cpu_combined, sizeof(uint8_t)*10); - mav_array_memcpy(packet.gpu_cores, gpu_cores, sizeof(uint8_t)*4); - mav_array_memcpy(packet.gpu_combined, gpu_combined, sizeof(uint8_t)*10); - mav_array_memcpy(packet.temperature_core, temperature_core, sizeof(int8_t)*8); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ONBOARD_COMPUTER_STATUS_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_ONBOARD_COMPUTER_STATUS; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ONBOARD_COMPUTER_STATUS_MIN_LEN, MAVLINK_MSG_ID_ONBOARD_COMPUTER_STATUS_LEN, MAVLINK_MSG_ID_ONBOARD_COMPUTER_STATUS_CRC); -} - -/** - * @brief Encode a onboard_computer_status struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param onboard_computer_status C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_onboard_computer_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_onboard_computer_status_t* onboard_computer_status) -{ - return mavlink_msg_onboard_computer_status_pack(system_id, component_id, msg, onboard_computer_status->time_usec, onboard_computer_status->uptime, onboard_computer_status->type, onboard_computer_status->cpu_cores, onboard_computer_status->cpu_combined, onboard_computer_status->gpu_cores, onboard_computer_status->gpu_combined, onboard_computer_status->temperature_board, onboard_computer_status->temperature_core, onboard_computer_status->fan_speed, onboard_computer_status->ram_usage, onboard_computer_status->ram_total, onboard_computer_status->storage_type, onboard_computer_status->storage_usage, onboard_computer_status->storage_total, onboard_computer_status->link_type, onboard_computer_status->link_tx_rate, onboard_computer_status->link_rx_rate, onboard_computer_status->link_tx_max, onboard_computer_status->link_rx_max); -} - -/** - * @brief Encode a onboard_computer_status struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param onboard_computer_status C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_onboard_computer_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_onboard_computer_status_t* onboard_computer_status) -{ - return mavlink_msg_onboard_computer_status_pack_chan(system_id, component_id, chan, msg, onboard_computer_status->time_usec, onboard_computer_status->uptime, onboard_computer_status->type, onboard_computer_status->cpu_cores, onboard_computer_status->cpu_combined, onboard_computer_status->gpu_cores, onboard_computer_status->gpu_combined, onboard_computer_status->temperature_board, onboard_computer_status->temperature_core, onboard_computer_status->fan_speed, onboard_computer_status->ram_usage, onboard_computer_status->ram_total, onboard_computer_status->storage_type, onboard_computer_status->storage_usage, onboard_computer_status->storage_total, onboard_computer_status->link_type, onboard_computer_status->link_tx_rate, onboard_computer_status->link_rx_rate, onboard_computer_status->link_tx_max, onboard_computer_status->link_rx_max); -} - -/** - * @brief Send a onboard_computer_status message - * @param chan MAVLink channel to send the message - * - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @param uptime [ms] Time since system boot. - * @param type Type of the onboard computer: 0: Mission computer primary, 1: Mission computer backup 1, 2: Mission computer backup 2, 3: Compute node, 4-5: Compute spares, 6-9: Payload computers. - * @param cpu_cores CPU usage on the component in percent (100 - idle). A value of UINT8_MAX implies the field is unused. - * @param cpu_combined Combined CPU usage as the last 10 slices of 100 MS (a histogram). This allows to identify spikes in load that max out the system, but only for a short amount of time. A value of UINT8_MAX implies the field is unused. - * @param gpu_cores GPU usage on the component in percent (100 - idle). A value of UINT8_MAX implies the field is unused. - * @param gpu_combined Combined GPU usage as the last 10 slices of 100 MS (a histogram). This allows to identify spikes in load that max out the system, but only for a short amount of time. A value of UINT8_MAX implies the field is unused. - * @param temperature_board [degC] Temperature of the board. A value of INT8_MAX implies the field is unused. - * @param temperature_core [degC] Temperature of the CPU core. A value of INT8_MAX implies the field is unused. - * @param fan_speed [rpm] Fan speeds. A value of INT16_MAX implies the field is unused. - * @param ram_usage [MiB] Amount of used RAM on the component system. A value of UINT32_MAX implies the field is unused. - * @param ram_total [MiB] Total amount of RAM on the component system. A value of UINT32_MAX implies the field is unused. - * @param storage_type Storage type: 0: HDD, 1: SSD, 2: EMMC, 3: SD card (non-removable), 4: SD card (removable). A value of UINT32_MAX implies the field is unused. - * @param storage_usage [MiB] Amount of used storage space on the component system. A value of UINT32_MAX implies the field is unused. - * @param storage_total [MiB] Total amount of storage space on the component system. A value of UINT32_MAX implies the field is unused. - * @param link_type Link type: 0-9: UART, 10-19: Wired network, 20-29: Wifi, 30-39: Point-to-point proprietary, 40-49: Mesh proprietary - * @param link_tx_rate [KiB/s] Network traffic from the component system. A value of UINT32_MAX implies the field is unused. - * @param link_rx_rate [KiB/s] Network traffic to the component system. A value of UINT32_MAX implies the field is unused. - * @param link_tx_max [KiB/s] Network capacity from the component system. A value of UINT32_MAX implies the field is unused. - * @param link_rx_max [KiB/s] Network capacity to the component system. A value of UINT32_MAX implies the field is unused. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_onboard_computer_status_send(mavlink_channel_t chan, uint64_t time_usec, uint32_t uptime, uint8_t type, const uint8_t *cpu_cores, const uint8_t *cpu_combined, const uint8_t *gpu_cores, const uint8_t *gpu_combined, int8_t temperature_board, const int8_t *temperature_core, const int16_t *fan_speed, uint32_t ram_usage, uint32_t ram_total, const uint32_t *storage_type, const uint32_t *storage_usage, const uint32_t *storage_total, const uint32_t *link_type, const uint32_t *link_tx_rate, const uint32_t *link_rx_rate, const uint32_t *link_tx_max, const uint32_t *link_rx_max) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_ONBOARD_COMPUTER_STATUS_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint32_t(buf, 8, uptime); - _mav_put_uint32_t(buf, 12, ram_usage); - _mav_put_uint32_t(buf, 16, ram_total); - _mav_put_uint8_t(buf, 196, type); - _mav_put_int8_t(buf, 229, temperature_board); - _mav_put_uint32_t_array(buf, 20, storage_type, 4); - _mav_put_uint32_t_array(buf, 36, storage_usage, 4); - _mav_put_uint32_t_array(buf, 52, storage_total, 4); - _mav_put_uint32_t_array(buf, 68, link_type, 6); - _mav_put_uint32_t_array(buf, 92, link_tx_rate, 6); - _mav_put_uint32_t_array(buf, 116, link_rx_rate, 6); - _mav_put_uint32_t_array(buf, 140, link_tx_max, 6); - _mav_put_uint32_t_array(buf, 164, link_rx_max, 6); - _mav_put_int16_t_array(buf, 188, fan_speed, 4); - _mav_put_uint8_t_array(buf, 197, cpu_cores, 8); - _mav_put_uint8_t_array(buf, 205, cpu_combined, 10); - _mav_put_uint8_t_array(buf, 215, gpu_cores, 4); - _mav_put_uint8_t_array(buf, 219, gpu_combined, 10); - _mav_put_int8_t_array(buf, 230, temperature_core, 8); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ONBOARD_COMPUTER_STATUS, buf, MAVLINK_MSG_ID_ONBOARD_COMPUTER_STATUS_MIN_LEN, MAVLINK_MSG_ID_ONBOARD_COMPUTER_STATUS_LEN, MAVLINK_MSG_ID_ONBOARD_COMPUTER_STATUS_CRC); -#else - mavlink_onboard_computer_status_t packet; - packet.time_usec = time_usec; - packet.uptime = uptime; - packet.ram_usage = ram_usage; - packet.ram_total = ram_total; - packet.type = type; - packet.temperature_board = temperature_board; - mav_array_memcpy(packet.storage_type, storage_type, sizeof(uint32_t)*4); - mav_array_memcpy(packet.storage_usage, storage_usage, sizeof(uint32_t)*4); - mav_array_memcpy(packet.storage_total, storage_total, sizeof(uint32_t)*4); - mav_array_memcpy(packet.link_type, link_type, sizeof(uint32_t)*6); - mav_array_memcpy(packet.link_tx_rate, link_tx_rate, sizeof(uint32_t)*6); - mav_array_memcpy(packet.link_rx_rate, link_rx_rate, sizeof(uint32_t)*6); - mav_array_memcpy(packet.link_tx_max, link_tx_max, sizeof(uint32_t)*6); - mav_array_memcpy(packet.link_rx_max, link_rx_max, sizeof(uint32_t)*6); - mav_array_memcpy(packet.fan_speed, fan_speed, sizeof(int16_t)*4); - mav_array_memcpy(packet.cpu_cores, cpu_cores, sizeof(uint8_t)*8); - mav_array_memcpy(packet.cpu_combined, cpu_combined, sizeof(uint8_t)*10); - mav_array_memcpy(packet.gpu_cores, gpu_cores, sizeof(uint8_t)*4); - mav_array_memcpy(packet.gpu_combined, gpu_combined, sizeof(uint8_t)*10); - mav_array_memcpy(packet.temperature_core, temperature_core, sizeof(int8_t)*8); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ONBOARD_COMPUTER_STATUS, (const char *)&packet, MAVLINK_MSG_ID_ONBOARD_COMPUTER_STATUS_MIN_LEN, MAVLINK_MSG_ID_ONBOARD_COMPUTER_STATUS_LEN, MAVLINK_MSG_ID_ONBOARD_COMPUTER_STATUS_CRC); -#endif -} - -/** - * @brief Send a onboard_computer_status message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_onboard_computer_status_send_struct(mavlink_channel_t chan, const mavlink_onboard_computer_status_t* onboard_computer_status) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_onboard_computer_status_send(chan, onboard_computer_status->time_usec, onboard_computer_status->uptime, onboard_computer_status->type, onboard_computer_status->cpu_cores, onboard_computer_status->cpu_combined, onboard_computer_status->gpu_cores, onboard_computer_status->gpu_combined, onboard_computer_status->temperature_board, onboard_computer_status->temperature_core, onboard_computer_status->fan_speed, onboard_computer_status->ram_usage, onboard_computer_status->ram_total, onboard_computer_status->storage_type, onboard_computer_status->storage_usage, onboard_computer_status->storage_total, onboard_computer_status->link_type, onboard_computer_status->link_tx_rate, onboard_computer_status->link_rx_rate, onboard_computer_status->link_tx_max, onboard_computer_status->link_rx_max); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ONBOARD_COMPUTER_STATUS, (const char *)onboard_computer_status, MAVLINK_MSG_ID_ONBOARD_COMPUTER_STATUS_MIN_LEN, MAVLINK_MSG_ID_ONBOARD_COMPUTER_STATUS_LEN, MAVLINK_MSG_ID_ONBOARD_COMPUTER_STATUS_CRC); -#endif -} - -#if MAVLINK_MSG_ID_ONBOARD_COMPUTER_STATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_onboard_computer_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, uint32_t uptime, uint8_t type, const uint8_t *cpu_cores, const uint8_t *cpu_combined, const uint8_t *gpu_cores, const uint8_t *gpu_combined, int8_t temperature_board, const int8_t *temperature_core, const int16_t *fan_speed, uint32_t ram_usage, uint32_t ram_total, const uint32_t *storage_type, const uint32_t *storage_usage, const uint32_t *storage_total, const uint32_t *link_type, const uint32_t *link_tx_rate, const uint32_t *link_rx_rate, const uint32_t *link_tx_max, const uint32_t *link_rx_max) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint32_t(buf, 8, uptime); - _mav_put_uint32_t(buf, 12, ram_usage); - _mav_put_uint32_t(buf, 16, ram_total); - _mav_put_uint8_t(buf, 196, type); - _mav_put_int8_t(buf, 229, temperature_board); - _mav_put_uint32_t_array(buf, 20, storage_type, 4); - _mav_put_uint32_t_array(buf, 36, storage_usage, 4); - _mav_put_uint32_t_array(buf, 52, storage_total, 4); - _mav_put_uint32_t_array(buf, 68, link_type, 6); - _mav_put_uint32_t_array(buf, 92, link_tx_rate, 6); - _mav_put_uint32_t_array(buf, 116, link_rx_rate, 6); - _mav_put_uint32_t_array(buf, 140, link_tx_max, 6); - _mav_put_uint32_t_array(buf, 164, link_rx_max, 6); - _mav_put_int16_t_array(buf, 188, fan_speed, 4); - _mav_put_uint8_t_array(buf, 197, cpu_cores, 8); - _mav_put_uint8_t_array(buf, 205, cpu_combined, 10); - _mav_put_uint8_t_array(buf, 215, gpu_cores, 4); - _mav_put_uint8_t_array(buf, 219, gpu_combined, 10); - _mav_put_int8_t_array(buf, 230, temperature_core, 8); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ONBOARD_COMPUTER_STATUS, buf, MAVLINK_MSG_ID_ONBOARD_COMPUTER_STATUS_MIN_LEN, MAVLINK_MSG_ID_ONBOARD_COMPUTER_STATUS_LEN, MAVLINK_MSG_ID_ONBOARD_COMPUTER_STATUS_CRC); -#else - mavlink_onboard_computer_status_t *packet = (mavlink_onboard_computer_status_t *)msgbuf; - packet->time_usec = time_usec; - packet->uptime = uptime; - packet->ram_usage = ram_usage; - packet->ram_total = ram_total; - packet->type = type; - packet->temperature_board = temperature_board; - mav_array_memcpy(packet->storage_type, storage_type, sizeof(uint32_t)*4); - mav_array_memcpy(packet->storage_usage, storage_usage, sizeof(uint32_t)*4); - mav_array_memcpy(packet->storage_total, storage_total, sizeof(uint32_t)*4); - mav_array_memcpy(packet->link_type, link_type, sizeof(uint32_t)*6); - mav_array_memcpy(packet->link_tx_rate, link_tx_rate, sizeof(uint32_t)*6); - mav_array_memcpy(packet->link_rx_rate, link_rx_rate, sizeof(uint32_t)*6); - mav_array_memcpy(packet->link_tx_max, link_tx_max, sizeof(uint32_t)*6); - mav_array_memcpy(packet->link_rx_max, link_rx_max, sizeof(uint32_t)*6); - mav_array_memcpy(packet->fan_speed, fan_speed, sizeof(int16_t)*4); - mav_array_memcpy(packet->cpu_cores, cpu_cores, sizeof(uint8_t)*8); - mav_array_memcpy(packet->cpu_combined, cpu_combined, sizeof(uint8_t)*10); - mav_array_memcpy(packet->gpu_cores, gpu_cores, sizeof(uint8_t)*4); - mav_array_memcpy(packet->gpu_combined, gpu_combined, sizeof(uint8_t)*10); - mav_array_memcpy(packet->temperature_core, temperature_core, sizeof(int8_t)*8); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ONBOARD_COMPUTER_STATUS, (const char *)packet, MAVLINK_MSG_ID_ONBOARD_COMPUTER_STATUS_MIN_LEN, MAVLINK_MSG_ID_ONBOARD_COMPUTER_STATUS_LEN, MAVLINK_MSG_ID_ONBOARD_COMPUTER_STATUS_CRC); -#endif -} -#endif - -#endif - -// MESSAGE ONBOARD_COMPUTER_STATUS UNPACKING - - -/** - * @brief Get field time_usec from onboard_computer_status message - * - * @return [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - */ -static inline uint64_t mavlink_msg_onboard_computer_status_get_time_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field uptime from onboard_computer_status message - * - * @return [ms] Time since system boot. - */ -static inline uint32_t mavlink_msg_onboard_computer_status_get_uptime(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 8); -} - -/** - * @brief Get field type from onboard_computer_status message - * - * @return Type of the onboard computer: 0: Mission computer primary, 1: Mission computer backup 1, 2: Mission computer backup 2, 3: Compute node, 4-5: Compute spares, 6-9: Payload computers. - */ -static inline uint8_t mavlink_msg_onboard_computer_status_get_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 196); -} - -/** - * @brief Get field cpu_cores from onboard_computer_status message - * - * @return CPU usage on the component in percent (100 - idle). A value of UINT8_MAX implies the field is unused. - */ -static inline uint16_t mavlink_msg_onboard_computer_status_get_cpu_cores(const mavlink_message_t* msg, uint8_t *cpu_cores) -{ - return _MAV_RETURN_uint8_t_array(msg, cpu_cores, 8, 197); -} - -/** - * @brief Get field cpu_combined from onboard_computer_status message - * - * @return Combined CPU usage as the last 10 slices of 100 MS (a histogram). This allows to identify spikes in load that max out the system, but only for a short amount of time. A value of UINT8_MAX implies the field is unused. - */ -static inline uint16_t mavlink_msg_onboard_computer_status_get_cpu_combined(const mavlink_message_t* msg, uint8_t *cpu_combined) -{ - return _MAV_RETURN_uint8_t_array(msg, cpu_combined, 10, 205); -} - -/** - * @brief Get field gpu_cores from onboard_computer_status message - * - * @return GPU usage on the component in percent (100 - idle). A value of UINT8_MAX implies the field is unused. - */ -static inline uint16_t mavlink_msg_onboard_computer_status_get_gpu_cores(const mavlink_message_t* msg, uint8_t *gpu_cores) -{ - return _MAV_RETURN_uint8_t_array(msg, gpu_cores, 4, 215); -} - -/** - * @brief Get field gpu_combined from onboard_computer_status message - * - * @return Combined GPU usage as the last 10 slices of 100 MS (a histogram). This allows to identify spikes in load that max out the system, but only for a short amount of time. A value of UINT8_MAX implies the field is unused. - */ -static inline uint16_t mavlink_msg_onboard_computer_status_get_gpu_combined(const mavlink_message_t* msg, uint8_t *gpu_combined) -{ - return _MAV_RETURN_uint8_t_array(msg, gpu_combined, 10, 219); -} - -/** - * @brief Get field temperature_board from onboard_computer_status message - * - * @return [degC] Temperature of the board. A value of INT8_MAX implies the field is unused. - */ -static inline int8_t mavlink_msg_onboard_computer_status_get_temperature_board(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int8_t(msg, 229); -} - -/** - * @brief Get field temperature_core from onboard_computer_status message - * - * @return [degC] Temperature of the CPU core. A value of INT8_MAX implies the field is unused. - */ -static inline uint16_t mavlink_msg_onboard_computer_status_get_temperature_core(const mavlink_message_t* msg, int8_t *temperature_core) -{ - return _MAV_RETURN_int8_t_array(msg, temperature_core, 8, 230); -} - -/** - * @brief Get field fan_speed from onboard_computer_status message - * - * @return [rpm] Fan speeds. A value of INT16_MAX implies the field is unused. - */ -static inline uint16_t mavlink_msg_onboard_computer_status_get_fan_speed(const mavlink_message_t* msg, int16_t *fan_speed) -{ - return _MAV_RETURN_int16_t_array(msg, fan_speed, 4, 188); -} - -/** - * @brief Get field ram_usage from onboard_computer_status message - * - * @return [MiB] Amount of used RAM on the component system. A value of UINT32_MAX implies the field is unused. - */ -static inline uint32_t mavlink_msg_onboard_computer_status_get_ram_usage(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 12); -} - -/** - * @brief Get field ram_total from onboard_computer_status message - * - * @return [MiB] Total amount of RAM on the component system. A value of UINT32_MAX implies the field is unused. - */ -static inline uint32_t mavlink_msg_onboard_computer_status_get_ram_total(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 16); -} - -/** - * @brief Get field storage_type from onboard_computer_status message - * - * @return Storage type: 0: HDD, 1: SSD, 2: EMMC, 3: SD card (non-removable), 4: SD card (removable). A value of UINT32_MAX implies the field is unused. - */ -static inline uint16_t mavlink_msg_onboard_computer_status_get_storage_type(const mavlink_message_t* msg, uint32_t *storage_type) -{ - return _MAV_RETURN_uint32_t_array(msg, storage_type, 4, 20); -} - -/** - * @brief Get field storage_usage from onboard_computer_status message - * - * @return [MiB] Amount of used storage space on the component system. A value of UINT32_MAX implies the field is unused. - */ -static inline uint16_t mavlink_msg_onboard_computer_status_get_storage_usage(const mavlink_message_t* msg, uint32_t *storage_usage) -{ - return _MAV_RETURN_uint32_t_array(msg, storage_usage, 4, 36); -} - -/** - * @brief Get field storage_total from onboard_computer_status message - * - * @return [MiB] Total amount of storage space on the component system. A value of UINT32_MAX implies the field is unused. - */ -static inline uint16_t mavlink_msg_onboard_computer_status_get_storage_total(const mavlink_message_t* msg, uint32_t *storage_total) -{ - return _MAV_RETURN_uint32_t_array(msg, storage_total, 4, 52); -} - -/** - * @brief Get field link_type from onboard_computer_status message - * - * @return Link type: 0-9: UART, 10-19: Wired network, 20-29: Wifi, 30-39: Point-to-point proprietary, 40-49: Mesh proprietary - */ -static inline uint16_t mavlink_msg_onboard_computer_status_get_link_type(const mavlink_message_t* msg, uint32_t *link_type) -{ - return _MAV_RETURN_uint32_t_array(msg, link_type, 6, 68); -} - -/** - * @brief Get field link_tx_rate from onboard_computer_status message - * - * @return [KiB/s] Network traffic from the component system. A value of UINT32_MAX implies the field is unused. - */ -static inline uint16_t mavlink_msg_onboard_computer_status_get_link_tx_rate(const mavlink_message_t* msg, uint32_t *link_tx_rate) -{ - return _MAV_RETURN_uint32_t_array(msg, link_tx_rate, 6, 92); -} - -/** - * @brief Get field link_rx_rate from onboard_computer_status message - * - * @return [KiB/s] Network traffic to the component system. A value of UINT32_MAX implies the field is unused. - */ -static inline uint16_t mavlink_msg_onboard_computer_status_get_link_rx_rate(const mavlink_message_t* msg, uint32_t *link_rx_rate) -{ - return _MAV_RETURN_uint32_t_array(msg, link_rx_rate, 6, 116); -} - -/** - * @brief Get field link_tx_max from onboard_computer_status message - * - * @return [KiB/s] Network capacity from the component system. A value of UINT32_MAX implies the field is unused. - */ -static inline uint16_t mavlink_msg_onboard_computer_status_get_link_tx_max(const mavlink_message_t* msg, uint32_t *link_tx_max) -{ - return _MAV_RETURN_uint32_t_array(msg, link_tx_max, 6, 140); -} - -/** - * @brief Get field link_rx_max from onboard_computer_status message - * - * @return [KiB/s] Network capacity to the component system. A value of UINT32_MAX implies the field is unused. - */ -static inline uint16_t mavlink_msg_onboard_computer_status_get_link_rx_max(const mavlink_message_t* msg, uint32_t *link_rx_max) -{ - return _MAV_RETURN_uint32_t_array(msg, link_rx_max, 6, 164); -} - -/** - * @brief Decode a onboard_computer_status message into a struct - * - * @param msg The message to decode - * @param onboard_computer_status C-struct to decode the message contents into - */ -static inline void mavlink_msg_onboard_computer_status_decode(const mavlink_message_t* msg, mavlink_onboard_computer_status_t* onboard_computer_status) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - onboard_computer_status->time_usec = mavlink_msg_onboard_computer_status_get_time_usec(msg); - onboard_computer_status->uptime = mavlink_msg_onboard_computer_status_get_uptime(msg); - onboard_computer_status->ram_usage = mavlink_msg_onboard_computer_status_get_ram_usage(msg); - onboard_computer_status->ram_total = mavlink_msg_onboard_computer_status_get_ram_total(msg); - mavlink_msg_onboard_computer_status_get_storage_type(msg, onboard_computer_status->storage_type); - mavlink_msg_onboard_computer_status_get_storage_usage(msg, onboard_computer_status->storage_usage); - mavlink_msg_onboard_computer_status_get_storage_total(msg, onboard_computer_status->storage_total); - mavlink_msg_onboard_computer_status_get_link_type(msg, onboard_computer_status->link_type); - mavlink_msg_onboard_computer_status_get_link_tx_rate(msg, onboard_computer_status->link_tx_rate); - mavlink_msg_onboard_computer_status_get_link_rx_rate(msg, onboard_computer_status->link_rx_rate); - mavlink_msg_onboard_computer_status_get_link_tx_max(msg, onboard_computer_status->link_tx_max); - mavlink_msg_onboard_computer_status_get_link_rx_max(msg, onboard_computer_status->link_rx_max); - mavlink_msg_onboard_computer_status_get_fan_speed(msg, onboard_computer_status->fan_speed); - onboard_computer_status->type = mavlink_msg_onboard_computer_status_get_type(msg); - mavlink_msg_onboard_computer_status_get_cpu_cores(msg, onboard_computer_status->cpu_cores); - mavlink_msg_onboard_computer_status_get_cpu_combined(msg, onboard_computer_status->cpu_combined); - mavlink_msg_onboard_computer_status_get_gpu_cores(msg, onboard_computer_status->gpu_cores); - mavlink_msg_onboard_computer_status_get_gpu_combined(msg, onboard_computer_status->gpu_combined); - onboard_computer_status->temperature_board = mavlink_msg_onboard_computer_status_get_temperature_board(msg); - mavlink_msg_onboard_computer_status_get_temperature_core(msg, onboard_computer_status->temperature_core); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_ONBOARD_COMPUTER_STATUS_LEN? msg->len : MAVLINK_MSG_ID_ONBOARD_COMPUTER_STATUS_LEN; - memset(onboard_computer_status, 0, MAVLINK_MSG_ID_ONBOARD_COMPUTER_STATUS_LEN); - memcpy(onboard_computer_status, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_open_drone_id_arm_status.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_open_drone_id_arm_status.h deleted file mode 100644 index d715499f..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_open_drone_id_arm_status.h +++ /dev/null @@ -1,230 +0,0 @@ -#pragma once -// MESSAGE OPEN_DRONE_ID_ARM_STATUS PACKING - -#define MAVLINK_MSG_ID_OPEN_DRONE_ID_ARM_STATUS 12918 - - -typedef struct __mavlink_open_drone_id_arm_status_t { - uint8_t status; /*< Status level indicating if arming is allowed.*/ - char error[50]; /*< Text error message, should be empty if status is good to arm. Fill with nulls in unused portion.*/ -} mavlink_open_drone_id_arm_status_t; - -#define MAVLINK_MSG_ID_OPEN_DRONE_ID_ARM_STATUS_LEN 51 -#define MAVLINK_MSG_ID_OPEN_DRONE_ID_ARM_STATUS_MIN_LEN 51 -#define MAVLINK_MSG_ID_12918_LEN 51 -#define MAVLINK_MSG_ID_12918_MIN_LEN 51 - -#define MAVLINK_MSG_ID_OPEN_DRONE_ID_ARM_STATUS_CRC 139 -#define MAVLINK_MSG_ID_12918_CRC 139 - -#define MAVLINK_MSG_OPEN_DRONE_ID_ARM_STATUS_FIELD_ERROR_LEN 50 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_OPEN_DRONE_ID_ARM_STATUS { \ - 12918, \ - "OPEN_DRONE_ID_ARM_STATUS", \ - 2, \ - { { "status", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_open_drone_id_arm_status_t, status) }, \ - { "error", NULL, MAVLINK_TYPE_CHAR, 50, 1, offsetof(mavlink_open_drone_id_arm_status_t, error) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_OPEN_DRONE_ID_ARM_STATUS { \ - "OPEN_DRONE_ID_ARM_STATUS", \ - 2, \ - { { "status", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_open_drone_id_arm_status_t, status) }, \ - { "error", NULL, MAVLINK_TYPE_CHAR, 50, 1, offsetof(mavlink_open_drone_id_arm_status_t, error) }, \ - } \ -} -#endif - -/** - * @brief Pack a open_drone_id_arm_status message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param status Status level indicating if arming is allowed. - * @param error Text error message, should be empty if status is good to arm. Fill with nulls in unused portion. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_open_drone_id_arm_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t status, const char *error) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_OPEN_DRONE_ID_ARM_STATUS_LEN]; - _mav_put_uint8_t(buf, 0, status); - _mav_put_char_array(buf, 1, error, 50); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OPEN_DRONE_ID_ARM_STATUS_LEN); -#else - mavlink_open_drone_id_arm_status_t packet; - packet.status = status; - mav_array_memcpy(packet.error, error, sizeof(char)*50); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_OPEN_DRONE_ID_ARM_STATUS_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_OPEN_DRONE_ID_ARM_STATUS; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_OPEN_DRONE_ID_ARM_STATUS_MIN_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_ARM_STATUS_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_ARM_STATUS_CRC); -} - -/** - * @brief Pack a open_drone_id_arm_status message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param status Status level indicating if arming is allowed. - * @param error Text error message, should be empty if status is good to arm. Fill with nulls in unused portion. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_open_drone_id_arm_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t status,const char *error) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_OPEN_DRONE_ID_ARM_STATUS_LEN]; - _mav_put_uint8_t(buf, 0, status); - _mav_put_char_array(buf, 1, error, 50); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OPEN_DRONE_ID_ARM_STATUS_LEN); -#else - mavlink_open_drone_id_arm_status_t packet; - packet.status = status; - mav_array_memcpy(packet.error, error, sizeof(char)*50); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_OPEN_DRONE_ID_ARM_STATUS_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_OPEN_DRONE_ID_ARM_STATUS; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_OPEN_DRONE_ID_ARM_STATUS_MIN_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_ARM_STATUS_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_ARM_STATUS_CRC); -} - -/** - * @brief Encode a open_drone_id_arm_status struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param open_drone_id_arm_status C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_open_drone_id_arm_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_open_drone_id_arm_status_t* open_drone_id_arm_status) -{ - return mavlink_msg_open_drone_id_arm_status_pack(system_id, component_id, msg, open_drone_id_arm_status->status, open_drone_id_arm_status->error); -} - -/** - * @brief Encode a open_drone_id_arm_status struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param open_drone_id_arm_status C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_open_drone_id_arm_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_open_drone_id_arm_status_t* open_drone_id_arm_status) -{ - return mavlink_msg_open_drone_id_arm_status_pack_chan(system_id, component_id, chan, msg, open_drone_id_arm_status->status, open_drone_id_arm_status->error); -} - -/** - * @brief Send a open_drone_id_arm_status message - * @param chan MAVLink channel to send the message - * - * @param status Status level indicating if arming is allowed. - * @param error Text error message, should be empty if status is good to arm. Fill with nulls in unused portion. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_open_drone_id_arm_status_send(mavlink_channel_t chan, uint8_t status, const char *error) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_OPEN_DRONE_ID_ARM_STATUS_LEN]; - _mav_put_uint8_t(buf, 0, status); - _mav_put_char_array(buf, 1, error, 50); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPEN_DRONE_ID_ARM_STATUS, buf, MAVLINK_MSG_ID_OPEN_DRONE_ID_ARM_STATUS_MIN_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_ARM_STATUS_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_ARM_STATUS_CRC); -#else - mavlink_open_drone_id_arm_status_t packet; - packet.status = status; - mav_array_memcpy(packet.error, error, sizeof(char)*50); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPEN_DRONE_ID_ARM_STATUS, (const char *)&packet, MAVLINK_MSG_ID_OPEN_DRONE_ID_ARM_STATUS_MIN_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_ARM_STATUS_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_ARM_STATUS_CRC); -#endif -} - -/** - * @brief Send a open_drone_id_arm_status message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_open_drone_id_arm_status_send_struct(mavlink_channel_t chan, const mavlink_open_drone_id_arm_status_t* open_drone_id_arm_status) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_open_drone_id_arm_status_send(chan, open_drone_id_arm_status->status, open_drone_id_arm_status->error); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPEN_DRONE_ID_ARM_STATUS, (const char *)open_drone_id_arm_status, MAVLINK_MSG_ID_OPEN_DRONE_ID_ARM_STATUS_MIN_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_ARM_STATUS_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_ARM_STATUS_CRC); -#endif -} - -#if MAVLINK_MSG_ID_OPEN_DRONE_ID_ARM_STATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_open_drone_id_arm_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t status, const char *error) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint8_t(buf, 0, status); - _mav_put_char_array(buf, 1, error, 50); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPEN_DRONE_ID_ARM_STATUS, buf, MAVLINK_MSG_ID_OPEN_DRONE_ID_ARM_STATUS_MIN_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_ARM_STATUS_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_ARM_STATUS_CRC); -#else - mavlink_open_drone_id_arm_status_t *packet = (mavlink_open_drone_id_arm_status_t *)msgbuf; - packet->status = status; - mav_array_memcpy(packet->error, error, sizeof(char)*50); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPEN_DRONE_ID_ARM_STATUS, (const char *)packet, MAVLINK_MSG_ID_OPEN_DRONE_ID_ARM_STATUS_MIN_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_ARM_STATUS_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_ARM_STATUS_CRC); -#endif -} -#endif - -#endif - -// MESSAGE OPEN_DRONE_ID_ARM_STATUS UNPACKING - - -/** - * @brief Get field status from open_drone_id_arm_status message - * - * @return Status level indicating if arming is allowed. - */ -static inline uint8_t mavlink_msg_open_drone_id_arm_status_get_status(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 0); -} - -/** - * @brief Get field error from open_drone_id_arm_status message - * - * @return Text error message, should be empty if status is good to arm. Fill with nulls in unused portion. - */ -static inline uint16_t mavlink_msg_open_drone_id_arm_status_get_error(const mavlink_message_t* msg, char *error) -{ - return _MAV_RETURN_char_array(msg, error, 50, 1); -} - -/** - * @brief Decode a open_drone_id_arm_status message into a struct - * - * @param msg The message to decode - * @param open_drone_id_arm_status C-struct to decode the message contents into - */ -static inline void mavlink_msg_open_drone_id_arm_status_decode(const mavlink_message_t* msg, mavlink_open_drone_id_arm_status_t* open_drone_id_arm_status) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - open_drone_id_arm_status->status = mavlink_msg_open_drone_id_arm_status_get_status(msg); - mavlink_msg_open_drone_id_arm_status_get_error(msg, open_drone_id_arm_status->error); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_OPEN_DRONE_ID_ARM_STATUS_LEN? msg->len : MAVLINK_MSG_ID_OPEN_DRONE_ID_ARM_STATUS_LEN; - memset(open_drone_id_arm_status, 0, MAVLINK_MSG_ID_OPEN_DRONE_ID_ARM_STATUS_LEN); - memcpy(open_drone_id_arm_status, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_open_drone_id_authentication.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_open_drone_id_authentication.h deleted file mode 100644 index 4c5fc3a0..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_open_drone_id_authentication.h +++ /dev/null @@ -1,406 +0,0 @@ -#pragma once -// MESSAGE OPEN_DRONE_ID_AUTHENTICATION PACKING - -#define MAVLINK_MSG_ID_OPEN_DRONE_ID_AUTHENTICATION 12902 - - -typedef struct __mavlink_open_drone_id_authentication_t { - uint32_t timestamp; /*< [s] This field is only present for page 0. 32 bit Unix Timestamp in seconds since 00:00:00 01/01/2019.*/ - uint8_t target_system; /*< System ID (0 for broadcast).*/ - uint8_t target_component; /*< Component ID (0 for broadcast).*/ - uint8_t id_or_mac[20]; /*< Only used for drone ID data received from other UAs. See detailed description at https://mavlink.io/en/services/opendroneid.html. */ - uint8_t authentication_type; /*< Indicates the type of authentication.*/ - uint8_t data_page; /*< Allowed range is 0 - 15.*/ - uint8_t last_page_index; /*< This field is only present for page 0. Allowed range is 0 - 15. See the description of struct ODID_Auth_data at https://github.com/opendroneid/opendroneid-core-c/blob/master/libopendroneid/opendroneid.h.*/ - uint8_t length; /*< [bytes] This field is only present for page 0. Total bytes of authentication_data from all data pages. See the description of struct ODID_Auth_data at https://github.com/opendroneid/opendroneid-core-c/blob/master/libopendroneid/opendroneid.h.*/ - uint8_t authentication_data[23]; /*< Opaque authentication data. For page 0, the size is only 17 bytes. For other pages, the size is 23 bytes. Shall be filled with nulls in the unused portion of the field.*/ -} mavlink_open_drone_id_authentication_t; - -#define MAVLINK_MSG_ID_OPEN_DRONE_ID_AUTHENTICATION_LEN 53 -#define MAVLINK_MSG_ID_OPEN_DRONE_ID_AUTHENTICATION_MIN_LEN 53 -#define MAVLINK_MSG_ID_12902_LEN 53 -#define MAVLINK_MSG_ID_12902_MIN_LEN 53 - -#define MAVLINK_MSG_ID_OPEN_DRONE_ID_AUTHENTICATION_CRC 140 -#define MAVLINK_MSG_ID_12902_CRC 140 - -#define MAVLINK_MSG_OPEN_DRONE_ID_AUTHENTICATION_FIELD_ID_OR_MAC_LEN 20 -#define MAVLINK_MSG_OPEN_DRONE_ID_AUTHENTICATION_FIELD_AUTHENTICATION_DATA_LEN 23 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_OPEN_DRONE_ID_AUTHENTICATION { \ - 12902, \ - "OPEN_DRONE_ID_AUTHENTICATION", \ - 9, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_open_drone_id_authentication_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_open_drone_id_authentication_t, target_component) }, \ - { "id_or_mac", NULL, MAVLINK_TYPE_UINT8_T, 20, 6, offsetof(mavlink_open_drone_id_authentication_t, id_or_mac) }, \ - { "authentication_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 26, offsetof(mavlink_open_drone_id_authentication_t, authentication_type) }, \ - { "data_page", NULL, MAVLINK_TYPE_UINT8_T, 0, 27, offsetof(mavlink_open_drone_id_authentication_t, data_page) }, \ - { "last_page_index", NULL, MAVLINK_TYPE_UINT8_T, 0, 28, offsetof(mavlink_open_drone_id_authentication_t, last_page_index) }, \ - { "length", NULL, MAVLINK_TYPE_UINT8_T, 0, 29, offsetof(mavlink_open_drone_id_authentication_t, length) }, \ - { "timestamp", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_open_drone_id_authentication_t, timestamp) }, \ - { "authentication_data", NULL, MAVLINK_TYPE_UINT8_T, 23, 30, offsetof(mavlink_open_drone_id_authentication_t, authentication_data) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_OPEN_DRONE_ID_AUTHENTICATION { \ - "OPEN_DRONE_ID_AUTHENTICATION", \ - 9, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_open_drone_id_authentication_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_open_drone_id_authentication_t, target_component) }, \ - { "id_or_mac", NULL, MAVLINK_TYPE_UINT8_T, 20, 6, offsetof(mavlink_open_drone_id_authentication_t, id_or_mac) }, \ - { "authentication_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 26, offsetof(mavlink_open_drone_id_authentication_t, authentication_type) }, \ - { "data_page", NULL, MAVLINK_TYPE_UINT8_T, 0, 27, offsetof(mavlink_open_drone_id_authentication_t, data_page) }, \ - { "last_page_index", NULL, MAVLINK_TYPE_UINT8_T, 0, 28, offsetof(mavlink_open_drone_id_authentication_t, last_page_index) }, \ - { "length", NULL, MAVLINK_TYPE_UINT8_T, 0, 29, offsetof(mavlink_open_drone_id_authentication_t, length) }, \ - { "timestamp", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_open_drone_id_authentication_t, timestamp) }, \ - { "authentication_data", NULL, MAVLINK_TYPE_UINT8_T, 23, 30, offsetof(mavlink_open_drone_id_authentication_t, authentication_data) }, \ - } \ -} -#endif - -/** - * @brief Pack a open_drone_id_authentication message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID (0 for broadcast). - * @param target_component Component ID (0 for broadcast). - * @param id_or_mac Only used for drone ID data received from other UAs. See detailed description at https://mavlink.io/en/services/opendroneid.html. - * @param authentication_type Indicates the type of authentication. - * @param data_page Allowed range is 0 - 15. - * @param last_page_index This field is only present for page 0. Allowed range is 0 - 15. See the description of struct ODID_Auth_data at https://github.com/opendroneid/opendroneid-core-c/blob/master/libopendroneid/opendroneid.h. - * @param length [bytes] This field is only present for page 0. Total bytes of authentication_data from all data pages. See the description of struct ODID_Auth_data at https://github.com/opendroneid/opendroneid-core-c/blob/master/libopendroneid/opendroneid.h. - * @param timestamp [s] This field is only present for page 0. 32 bit Unix Timestamp in seconds since 00:00:00 01/01/2019. - * @param authentication_data Opaque authentication data. For page 0, the size is only 17 bytes. For other pages, the size is 23 bytes. Shall be filled with nulls in the unused portion of the field. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_open_drone_id_authentication_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component, const uint8_t *id_or_mac, uint8_t authentication_type, uint8_t data_page, uint8_t last_page_index, uint8_t length, uint32_t timestamp, const uint8_t *authentication_data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_OPEN_DRONE_ID_AUTHENTICATION_LEN]; - _mav_put_uint32_t(buf, 0, timestamp); - _mav_put_uint8_t(buf, 4, target_system); - _mav_put_uint8_t(buf, 5, target_component); - _mav_put_uint8_t(buf, 26, authentication_type); - _mav_put_uint8_t(buf, 27, data_page); - _mav_put_uint8_t(buf, 28, last_page_index); - _mav_put_uint8_t(buf, 29, length); - _mav_put_uint8_t_array(buf, 6, id_or_mac, 20); - _mav_put_uint8_t_array(buf, 30, authentication_data, 23); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OPEN_DRONE_ID_AUTHENTICATION_LEN); -#else - mavlink_open_drone_id_authentication_t packet; - packet.timestamp = timestamp; - packet.target_system = target_system; - packet.target_component = target_component; - packet.authentication_type = authentication_type; - packet.data_page = data_page; - packet.last_page_index = last_page_index; - packet.length = length; - mav_array_memcpy(packet.id_or_mac, id_or_mac, sizeof(uint8_t)*20); - mav_array_memcpy(packet.authentication_data, authentication_data, sizeof(uint8_t)*23); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_OPEN_DRONE_ID_AUTHENTICATION_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_OPEN_DRONE_ID_AUTHENTICATION; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_OPEN_DRONE_ID_AUTHENTICATION_MIN_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_AUTHENTICATION_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_AUTHENTICATION_CRC); -} - -/** - * @brief Pack a open_drone_id_authentication message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID (0 for broadcast). - * @param target_component Component ID (0 for broadcast). - * @param id_or_mac Only used for drone ID data received from other UAs. See detailed description at https://mavlink.io/en/services/opendroneid.html. - * @param authentication_type Indicates the type of authentication. - * @param data_page Allowed range is 0 - 15. - * @param last_page_index This field is only present for page 0. Allowed range is 0 - 15. See the description of struct ODID_Auth_data at https://github.com/opendroneid/opendroneid-core-c/blob/master/libopendroneid/opendroneid.h. - * @param length [bytes] This field is only present for page 0. Total bytes of authentication_data from all data pages. See the description of struct ODID_Auth_data at https://github.com/opendroneid/opendroneid-core-c/blob/master/libopendroneid/opendroneid.h. - * @param timestamp [s] This field is only present for page 0. 32 bit Unix Timestamp in seconds since 00:00:00 01/01/2019. - * @param authentication_data Opaque authentication data. For page 0, the size is only 17 bytes. For other pages, the size is 23 bytes. Shall be filled with nulls in the unused portion of the field. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_open_drone_id_authentication_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component,const uint8_t *id_or_mac,uint8_t authentication_type,uint8_t data_page,uint8_t last_page_index,uint8_t length,uint32_t timestamp,const uint8_t *authentication_data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_OPEN_DRONE_ID_AUTHENTICATION_LEN]; - _mav_put_uint32_t(buf, 0, timestamp); - _mav_put_uint8_t(buf, 4, target_system); - _mav_put_uint8_t(buf, 5, target_component); - _mav_put_uint8_t(buf, 26, authentication_type); - _mav_put_uint8_t(buf, 27, data_page); - _mav_put_uint8_t(buf, 28, last_page_index); - _mav_put_uint8_t(buf, 29, length); - _mav_put_uint8_t_array(buf, 6, id_or_mac, 20); - _mav_put_uint8_t_array(buf, 30, authentication_data, 23); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OPEN_DRONE_ID_AUTHENTICATION_LEN); -#else - mavlink_open_drone_id_authentication_t packet; - packet.timestamp = timestamp; - packet.target_system = target_system; - packet.target_component = target_component; - packet.authentication_type = authentication_type; - packet.data_page = data_page; - packet.last_page_index = last_page_index; - packet.length = length; - mav_array_memcpy(packet.id_or_mac, id_or_mac, sizeof(uint8_t)*20); - mav_array_memcpy(packet.authentication_data, authentication_data, sizeof(uint8_t)*23); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_OPEN_DRONE_ID_AUTHENTICATION_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_OPEN_DRONE_ID_AUTHENTICATION; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_OPEN_DRONE_ID_AUTHENTICATION_MIN_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_AUTHENTICATION_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_AUTHENTICATION_CRC); -} - -/** - * @brief Encode a open_drone_id_authentication struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param open_drone_id_authentication C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_open_drone_id_authentication_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_open_drone_id_authentication_t* open_drone_id_authentication) -{ - return mavlink_msg_open_drone_id_authentication_pack(system_id, component_id, msg, open_drone_id_authentication->target_system, open_drone_id_authentication->target_component, open_drone_id_authentication->id_or_mac, open_drone_id_authentication->authentication_type, open_drone_id_authentication->data_page, open_drone_id_authentication->last_page_index, open_drone_id_authentication->length, open_drone_id_authentication->timestamp, open_drone_id_authentication->authentication_data); -} - -/** - * @brief Encode a open_drone_id_authentication struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param open_drone_id_authentication C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_open_drone_id_authentication_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_open_drone_id_authentication_t* open_drone_id_authentication) -{ - return mavlink_msg_open_drone_id_authentication_pack_chan(system_id, component_id, chan, msg, open_drone_id_authentication->target_system, open_drone_id_authentication->target_component, open_drone_id_authentication->id_or_mac, open_drone_id_authentication->authentication_type, open_drone_id_authentication->data_page, open_drone_id_authentication->last_page_index, open_drone_id_authentication->length, open_drone_id_authentication->timestamp, open_drone_id_authentication->authentication_data); -} - -/** - * @brief Send a open_drone_id_authentication message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID (0 for broadcast). - * @param target_component Component ID (0 for broadcast). - * @param id_or_mac Only used for drone ID data received from other UAs. See detailed description at https://mavlink.io/en/services/opendroneid.html. - * @param authentication_type Indicates the type of authentication. - * @param data_page Allowed range is 0 - 15. - * @param last_page_index This field is only present for page 0. Allowed range is 0 - 15. See the description of struct ODID_Auth_data at https://github.com/opendroneid/opendroneid-core-c/blob/master/libopendroneid/opendroneid.h. - * @param length [bytes] This field is only present for page 0. Total bytes of authentication_data from all data pages. See the description of struct ODID_Auth_data at https://github.com/opendroneid/opendroneid-core-c/blob/master/libopendroneid/opendroneid.h. - * @param timestamp [s] This field is only present for page 0. 32 bit Unix Timestamp in seconds since 00:00:00 01/01/2019. - * @param authentication_data Opaque authentication data. For page 0, the size is only 17 bytes. For other pages, the size is 23 bytes. Shall be filled with nulls in the unused portion of the field. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_open_drone_id_authentication_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, const uint8_t *id_or_mac, uint8_t authentication_type, uint8_t data_page, uint8_t last_page_index, uint8_t length, uint32_t timestamp, const uint8_t *authentication_data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_OPEN_DRONE_ID_AUTHENTICATION_LEN]; - _mav_put_uint32_t(buf, 0, timestamp); - _mav_put_uint8_t(buf, 4, target_system); - _mav_put_uint8_t(buf, 5, target_component); - _mav_put_uint8_t(buf, 26, authentication_type); - _mav_put_uint8_t(buf, 27, data_page); - _mav_put_uint8_t(buf, 28, last_page_index); - _mav_put_uint8_t(buf, 29, length); - _mav_put_uint8_t_array(buf, 6, id_or_mac, 20); - _mav_put_uint8_t_array(buf, 30, authentication_data, 23); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPEN_DRONE_ID_AUTHENTICATION, buf, MAVLINK_MSG_ID_OPEN_DRONE_ID_AUTHENTICATION_MIN_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_AUTHENTICATION_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_AUTHENTICATION_CRC); -#else - mavlink_open_drone_id_authentication_t packet; - packet.timestamp = timestamp; - packet.target_system = target_system; - packet.target_component = target_component; - packet.authentication_type = authentication_type; - packet.data_page = data_page; - packet.last_page_index = last_page_index; - packet.length = length; - mav_array_memcpy(packet.id_or_mac, id_or_mac, sizeof(uint8_t)*20); - mav_array_memcpy(packet.authentication_data, authentication_data, sizeof(uint8_t)*23); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPEN_DRONE_ID_AUTHENTICATION, (const char *)&packet, MAVLINK_MSG_ID_OPEN_DRONE_ID_AUTHENTICATION_MIN_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_AUTHENTICATION_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_AUTHENTICATION_CRC); -#endif -} - -/** - * @brief Send a open_drone_id_authentication message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_open_drone_id_authentication_send_struct(mavlink_channel_t chan, const mavlink_open_drone_id_authentication_t* open_drone_id_authentication) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_open_drone_id_authentication_send(chan, open_drone_id_authentication->target_system, open_drone_id_authentication->target_component, open_drone_id_authentication->id_or_mac, open_drone_id_authentication->authentication_type, open_drone_id_authentication->data_page, open_drone_id_authentication->last_page_index, open_drone_id_authentication->length, open_drone_id_authentication->timestamp, open_drone_id_authentication->authentication_data); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPEN_DRONE_ID_AUTHENTICATION, (const char *)open_drone_id_authentication, MAVLINK_MSG_ID_OPEN_DRONE_ID_AUTHENTICATION_MIN_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_AUTHENTICATION_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_AUTHENTICATION_CRC); -#endif -} - -#if MAVLINK_MSG_ID_OPEN_DRONE_ID_AUTHENTICATION_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_open_drone_id_authentication_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, const uint8_t *id_or_mac, uint8_t authentication_type, uint8_t data_page, uint8_t last_page_index, uint8_t length, uint32_t timestamp, const uint8_t *authentication_data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, timestamp); - _mav_put_uint8_t(buf, 4, target_system); - _mav_put_uint8_t(buf, 5, target_component); - _mav_put_uint8_t(buf, 26, authentication_type); - _mav_put_uint8_t(buf, 27, data_page); - _mav_put_uint8_t(buf, 28, last_page_index); - _mav_put_uint8_t(buf, 29, length); - _mav_put_uint8_t_array(buf, 6, id_or_mac, 20); - _mav_put_uint8_t_array(buf, 30, authentication_data, 23); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPEN_DRONE_ID_AUTHENTICATION, buf, MAVLINK_MSG_ID_OPEN_DRONE_ID_AUTHENTICATION_MIN_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_AUTHENTICATION_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_AUTHENTICATION_CRC); -#else - mavlink_open_drone_id_authentication_t *packet = (mavlink_open_drone_id_authentication_t *)msgbuf; - packet->timestamp = timestamp; - packet->target_system = target_system; - packet->target_component = target_component; - packet->authentication_type = authentication_type; - packet->data_page = data_page; - packet->last_page_index = last_page_index; - packet->length = length; - mav_array_memcpy(packet->id_or_mac, id_or_mac, sizeof(uint8_t)*20); - mav_array_memcpy(packet->authentication_data, authentication_data, sizeof(uint8_t)*23); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPEN_DRONE_ID_AUTHENTICATION, (const char *)packet, MAVLINK_MSG_ID_OPEN_DRONE_ID_AUTHENTICATION_MIN_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_AUTHENTICATION_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_AUTHENTICATION_CRC); -#endif -} -#endif - -#endif - -// MESSAGE OPEN_DRONE_ID_AUTHENTICATION UNPACKING - - -/** - * @brief Get field target_system from open_drone_id_authentication message - * - * @return System ID (0 for broadcast). - */ -static inline uint8_t mavlink_msg_open_drone_id_authentication_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 4); -} - -/** - * @brief Get field target_component from open_drone_id_authentication message - * - * @return Component ID (0 for broadcast). - */ -static inline uint8_t mavlink_msg_open_drone_id_authentication_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 5); -} - -/** - * @brief Get field id_or_mac from open_drone_id_authentication message - * - * @return Only used for drone ID data received from other UAs. See detailed description at https://mavlink.io/en/services/opendroneid.html. - */ -static inline uint16_t mavlink_msg_open_drone_id_authentication_get_id_or_mac(const mavlink_message_t* msg, uint8_t *id_or_mac) -{ - return _MAV_RETURN_uint8_t_array(msg, id_or_mac, 20, 6); -} - -/** - * @brief Get field authentication_type from open_drone_id_authentication message - * - * @return Indicates the type of authentication. - */ -static inline uint8_t mavlink_msg_open_drone_id_authentication_get_authentication_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 26); -} - -/** - * @brief Get field data_page from open_drone_id_authentication message - * - * @return Allowed range is 0 - 15. - */ -static inline uint8_t mavlink_msg_open_drone_id_authentication_get_data_page(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 27); -} - -/** - * @brief Get field last_page_index from open_drone_id_authentication message - * - * @return This field is only present for page 0. Allowed range is 0 - 15. See the description of struct ODID_Auth_data at https://github.com/opendroneid/opendroneid-core-c/blob/master/libopendroneid/opendroneid.h. - */ -static inline uint8_t mavlink_msg_open_drone_id_authentication_get_last_page_index(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 28); -} - -/** - * @brief Get field length from open_drone_id_authentication message - * - * @return [bytes] This field is only present for page 0. Total bytes of authentication_data from all data pages. See the description of struct ODID_Auth_data at https://github.com/opendroneid/opendroneid-core-c/blob/master/libopendroneid/opendroneid.h. - */ -static inline uint8_t mavlink_msg_open_drone_id_authentication_get_length(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 29); -} - -/** - * @brief Get field timestamp from open_drone_id_authentication message - * - * @return [s] This field is only present for page 0. 32 bit Unix Timestamp in seconds since 00:00:00 01/01/2019. - */ -static inline uint32_t mavlink_msg_open_drone_id_authentication_get_timestamp(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field authentication_data from open_drone_id_authentication message - * - * @return Opaque authentication data. For page 0, the size is only 17 bytes. For other pages, the size is 23 bytes. Shall be filled with nulls in the unused portion of the field. - */ -static inline uint16_t mavlink_msg_open_drone_id_authentication_get_authentication_data(const mavlink_message_t* msg, uint8_t *authentication_data) -{ - return _MAV_RETURN_uint8_t_array(msg, authentication_data, 23, 30); -} - -/** - * @brief Decode a open_drone_id_authentication message into a struct - * - * @param msg The message to decode - * @param open_drone_id_authentication C-struct to decode the message contents into - */ -static inline void mavlink_msg_open_drone_id_authentication_decode(const mavlink_message_t* msg, mavlink_open_drone_id_authentication_t* open_drone_id_authentication) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - open_drone_id_authentication->timestamp = mavlink_msg_open_drone_id_authentication_get_timestamp(msg); - open_drone_id_authentication->target_system = mavlink_msg_open_drone_id_authentication_get_target_system(msg); - open_drone_id_authentication->target_component = mavlink_msg_open_drone_id_authentication_get_target_component(msg); - mavlink_msg_open_drone_id_authentication_get_id_or_mac(msg, open_drone_id_authentication->id_or_mac); - open_drone_id_authentication->authentication_type = mavlink_msg_open_drone_id_authentication_get_authentication_type(msg); - open_drone_id_authentication->data_page = mavlink_msg_open_drone_id_authentication_get_data_page(msg); - open_drone_id_authentication->last_page_index = mavlink_msg_open_drone_id_authentication_get_last_page_index(msg); - open_drone_id_authentication->length = mavlink_msg_open_drone_id_authentication_get_length(msg); - mavlink_msg_open_drone_id_authentication_get_authentication_data(msg, open_drone_id_authentication->authentication_data); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_OPEN_DRONE_ID_AUTHENTICATION_LEN? msg->len : MAVLINK_MSG_ID_OPEN_DRONE_ID_AUTHENTICATION_LEN; - memset(open_drone_id_authentication, 0, MAVLINK_MSG_ID_OPEN_DRONE_ID_AUTHENTICATION_LEN); - memcpy(open_drone_id_authentication, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_open_drone_id_basic_id.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_open_drone_id_basic_id.h deleted file mode 100644 index e2231451..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_open_drone_id_basic_id.h +++ /dev/null @@ -1,331 +0,0 @@ -#pragma once -// MESSAGE OPEN_DRONE_ID_BASIC_ID PACKING - -#define MAVLINK_MSG_ID_OPEN_DRONE_ID_BASIC_ID 12900 - - -typedef struct __mavlink_open_drone_id_basic_id_t { - uint8_t target_system; /*< System ID (0 for broadcast).*/ - uint8_t target_component; /*< Component ID (0 for broadcast).*/ - uint8_t id_or_mac[20]; /*< Only used for drone ID data received from other UAs. See detailed description at https://mavlink.io/en/services/opendroneid.html. */ - uint8_t id_type; /*< Indicates the format for the uas_id field of this message.*/ - uint8_t ua_type; /*< Indicates the type of UA (Unmanned Aircraft).*/ - uint8_t uas_id[20]; /*< UAS (Unmanned Aircraft System) ID following the format specified by id_type. Shall be filled with nulls in the unused portion of the field.*/ -} mavlink_open_drone_id_basic_id_t; - -#define MAVLINK_MSG_ID_OPEN_DRONE_ID_BASIC_ID_LEN 44 -#define MAVLINK_MSG_ID_OPEN_DRONE_ID_BASIC_ID_MIN_LEN 44 -#define MAVLINK_MSG_ID_12900_LEN 44 -#define MAVLINK_MSG_ID_12900_MIN_LEN 44 - -#define MAVLINK_MSG_ID_OPEN_DRONE_ID_BASIC_ID_CRC 114 -#define MAVLINK_MSG_ID_12900_CRC 114 - -#define MAVLINK_MSG_OPEN_DRONE_ID_BASIC_ID_FIELD_ID_OR_MAC_LEN 20 -#define MAVLINK_MSG_OPEN_DRONE_ID_BASIC_ID_FIELD_UAS_ID_LEN 20 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_OPEN_DRONE_ID_BASIC_ID { \ - 12900, \ - "OPEN_DRONE_ID_BASIC_ID", \ - 6, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_open_drone_id_basic_id_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_open_drone_id_basic_id_t, target_component) }, \ - { "id_or_mac", NULL, MAVLINK_TYPE_UINT8_T, 20, 2, offsetof(mavlink_open_drone_id_basic_id_t, id_or_mac) }, \ - { "id_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 22, offsetof(mavlink_open_drone_id_basic_id_t, id_type) }, \ - { "ua_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 23, offsetof(mavlink_open_drone_id_basic_id_t, ua_type) }, \ - { "uas_id", NULL, MAVLINK_TYPE_UINT8_T, 20, 24, offsetof(mavlink_open_drone_id_basic_id_t, uas_id) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_OPEN_DRONE_ID_BASIC_ID { \ - "OPEN_DRONE_ID_BASIC_ID", \ - 6, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_open_drone_id_basic_id_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_open_drone_id_basic_id_t, target_component) }, \ - { "id_or_mac", NULL, MAVLINK_TYPE_UINT8_T, 20, 2, offsetof(mavlink_open_drone_id_basic_id_t, id_or_mac) }, \ - { "id_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 22, offsetof(mavlink_open_drone_id_basic_id_t, id_type) }, \ - { "ua_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 23, offsetof(mavlink_open_drone_id_basic_id_t, ua_type) }, \ - { "uas_id", NULL, MAVLINK_TYPE_UINT8_T, 20, 24, offsetof(mavlink_open_drone_id_basic_id_t, uas_id) }, \ - } \ -} -#endif - -/** - * @brief Pack a open_drone_id_basic_id message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID (0 for broadcast). - * @param target_component Component ID (0 for broadcast). - * @param id_or_mac Only used for drone ID data received from other UAs. See detailed description at https://mavlink.io/en/services/opendroneid.html. - * @param id_type Indicates the format for the uas_id field of this message. - * @param ua_type Indicates the type of UA (Unmanned Aircraft). - * @param uas_id UAS (Unmanned Aircraft System) ID following the format specified by id_type. Shall be filled with nulls in the unused portion of the field. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_open_drone_id_basic_id_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component, const uint8_t *id_or_mac, uint8_t id_type, uint8_t ua_type, const uint8_t *uas_id) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_OPEN_DRONE_ID_BASIC_ID_LEN]; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - _mav_put_uint8_t(buf, 22, id_type); - _mav_put_uint8_t(buf, 23, ua_type); - _mav_put_uint8_t_array(buf, 2, id_or_mac, 20); - _mav_put_uint8_t_array(buf, 24, uas_id, 20); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OPEN_DRONE_ID_BASIC_ID_LEN); -#else - mavlink_open_drone_id_basic_id_t packet; - packet.target_system = target_system; - packet.target_component = target_component; - packet.id_type = id_type; - packet.ua_type = ua_type; - mav_array_memcpy(packet.id_or_mac, id_or_mac, sizeof(uint8_t)*20); - mav_array_memcpy(packet.uas_id, uas_id, sizeof(uint8_t)*20); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_OPEN_DRONE_ID_BASIC_ID_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_OPEN_DRONE_ID_BASIC_ID; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_OPEN_DRONE_ID_BASIC_ID_MIN_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_BASIC_ID_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_BASIC_ID_CRC); -} - -/** - * @brief Pack a open_drone_id_basic_id message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID (0 for broadcast). - * @param target_component Component ID (0 for broadcast). - * @param id_or_mac Only used for drone ID data received from other UAs. See detailed description at https://mavlink.io/en/services/opendroneid.html. - * @param id_type Indicates the format for the uas_id field of this message. - * @param ua_type Indicates the type of UA (Unmanned Aircraft). - * @param uas_id UAS (Unmanned Aircraft System) ID following the format specified by id_type. Shall be filled with nulls in the unused portion of the field. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_open_drone_id_basic_id_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component,const uint8_t *id_or_mac,uint8_t id_type,uint8_t ua_type,const uint8_t *uas_id) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_OPEN_DRONE_ID_BASIC_ID_LEN]; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - _mav_put_uint8_t(buf, 22, id_type); - _mav_put_uint8_t(buf, 23, ua_type); - _mav_put_uint8_t_array(buf, 2, id_or_mac, 20); - _mav_put_uint8_t_array(buf, 24, uas_id, 20); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OPEN_DRONE_ID_BASIC_ID_LEN); -#else - mavlink_open_drone_id_basic_id_t packet; - packet.target_system = target_system; - packet.target_component = target_component; - packet.id_type = id_type; - packet.ua_type = ua_type; - mav_array_memcpy(packet.id_or_mac, id_or_mac, sizeof(uint8_t)*20); - mav_array_memcpy(packet.uas_id, uas_id, sizeof(uint8_t)*20); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_OPEN_DRONE_ID_BASIC_ID_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_OPEN_DRONE_ID_BASIC_ID; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_OPEN_DRONE_ID_BASIC_ID_MIN_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_BASIC_ID_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_BASIC_ID_CRC); -} - -/** - * @brief Encode a open_drone_id_basic_id struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param open_drone_id_basic_id C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_open_drone_id_basic_id_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_open_drone_id_basic_id_t* open_drone_id_basic_id) -{ - return mavlink_msg_open_drone_id_basic_id_pack(system_id, component_id, msg, open_drone_id_basic_id->target_system, open_drone_id_basic_id->target_component, open_drone_id_basic_id->id_or_mac, open_drone_id_basic_id->id_type, open_drone_id_basic_id->ua_type, open_drone_id_basic_id->uas_id); -} - -/** - * @brief Encode a open_drone_id_basic_id struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param open_drone_id_basic_id C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_open_drone_id_basic_id_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_open_drone_id_basic_id_t* open_drone_id_basic_id) -{ - return mavlink_msg_open_drone_id_basic_id_pack_chan(system_id, component_id, chan, msg, open_drone_id_basic_id->target_system, open_drone_id_basic_id->target_component, open_drone_id_basic_id->id_or_mac, open_drone_id_basic_id->id_type, open_drone_id_basic_id->ua_type, open_drone_id_basic_id->uas_id); -} - -/** - * @brief Send a open_drone_id_basic_id message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID (0 for broadcast). - * @param target_component Component ID (0 for broadcast). - * @param id_or_mac Only used for drone ID data received from other UAs. See detailed description at https://mavlink.io/en/services/opendroneid.html. - * @param id_type Indicates the format for the uas_id field of this message. - * @param ua_type Indicates the type of UA (Unmanned Aircraft). - * @param uas_id UAS (Unmanned Aircraft System) ID following the format specified by id_type. Shall be filled with nulls in the unused portion of the field. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_open_drone_id_basic_id_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, const uint8_t *id_or_mac, uint8_t id_type, uint8_t ua_type, const uint8_t *uas_id) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_OPEN_DRONE_ID_BASIC_ID_LEN]; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - _mav_put_uint8_t(buf, 22, id_type); - _mav_put_uint8_t(buf, 23, ua_type); - _mav_put_uint8_t_array(buf, 2, id_or_mac, 20); - _mav_put_uint8_t_array(buf, 24, uas_id, 20); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPEN_DRONE_ID_BASIC_ID, buf, MAVLINK_MSG_ID_OPEN_DRONE_ID_BASIC_ID_MIN_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_BASIC_ID_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_BASIC_ID_CRC); -#else - mavlink_open_drone_id_basic_id_t packet; - packet.target_system = target_system; - packet.target_component = target_component; - packet.id_type = id_type; - packet.ua_type = ua_type; - mav_array_memcpy(packet.id_or_mac, id_or_mac, sizeof(uint8_t)*20); - mav_array_memcpy(packet.uas_id, uas_id, sizeof(uint8_t)*20); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPEN_DRONE_ID_BASIC_ID, (const char *)&packet, MAVLINK_MSG_ID_OPEN_DRONE_ID_BASIC_ID_MIN_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_BASIC_ID_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_BASIC_ID_CRC); -#endif -} - -/** - * @brief Send a open_drone_id_basic_id message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_open_drone_id_basic_id_send_struct(mavlink_channel_t chan, const mavlink_open_drone_id_basic_id_t* open_drone_id_basic_id) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_open_drone_id_basic_id_send(chan, open_drone_id_basic_id->target_system, open_drone_id_basic_id->target_component, open_drone_id_basic_id->id_or_mac, open_drone_id_basic_id->id_type, open_drone_id_basic_id->ua_type, open_drone_id_basic_id->uas_id); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPEN_DRONE_ID_BASIC_ID, (const char *)open_drone_id_basic_id, MAVLINK_MSG_ID_OPEN_DRONE_ID_BASIC_ID_MIN_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_BASIC_ID_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_BASIC_ID_CRC); -#endif -} - -#if MAVLINK_MSG_ID_OPEN_DRONE_ID_BASIC_ID_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_open_drone_id_basic_id_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, const uint8_t *id_or_mac, uint8_t id_type, uint8_t ua_type, const uint8_t *uas_id) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - _mav_put_uint8_t(buf, 22, id_type); - _mav_put_uint8_t(buf, 23, ua_type); - _mav_put_uint8_t_array(buf, 2, id_or_mac, 20); - _mav_put_uint8_t_array(buf, 24, uas_id, 20); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPEN_DRONE_ID_BASIC_ID, buf, MAVLINK_MSG_ID_OPEN_DRONE_ID_BASIC_ID_MIN_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_BASIC_ID_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_BASIC_ID_CRC); -#else - mavlink_open_drone_id_basic_id_t *packet = (mavlink_open_drone_id_basic_id_t *)msgbuf; - packet->target_system = target_system; - packet->target_component = target_component; - packet->id_type = id_type; - packet->ua_type = ua_type; - mav_array_memcpy(packet->id_or_mac, id_or_mac, sizeof(uint8_t)*20); - mav_array_memcpy(packet->uas_id, uas_id, sizeof(uint8_t)*20); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPEN_DRONE_ID_BASIC_ID, (const char *)packet, MAVLINK_MSG_ID_OPEN_DRONE_ID_BASIC_ID_MIN_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_BASIC_ID_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_BASIC_ID_CRC); -#endif -} -#endif - -#endif - -// MESSAGE OPEN_DRONE_ID_BASIC_ID UNPACKING - - -/** - * @brief Get field target_system from open_drone_id_basic_id message - * - * @return System ID (0 for broadcast). - */ -static inline uint8_t mavlink_msg_open_drone_id_basic_id_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 0); -} - -/** - * @brief Get field target_component from open_drone_id_basic_id message - * - * @return Component ID (0 for broadcast). - */ -static inline uint8_t mavlink_msg_open_drone_id_basic_id_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 1); -} - -/** - * @brief Get field id_or_mac from open_drone_id_basic_id message - * - * @return Only used for drone ID data received from other UAs. See detailed description at https://mavlink.io/en/services/opendroneid.html. - */ -static inline uint16_t mavlink_msg_open_drone_id_basic_id_get_id_or_mac(const mavlink_message_t* msg, uint8_t *id_or_mac) -{ - return _MAV_RETURN_uint8_t_array(msg, id_or_mac, 20, 2); -} - -/** - * @brief Get field id_type from open_drone_id_basic_id message - * - * @return Indicates the format for the uas_id field of this message. - */ -static inline uint8_t mavlink_msg_open_drone_id_basic_id_get_id_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 22); -} - -/** - * @brief Get field ua_type from open_drone_id_basic_id message - * - * @return Indicates the type of UA (Unmanned Aircraft). - */ -static inline uint8_t mavlink_msg_open_drone_id_basic_id_get_ua_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 23); -} - -/** - * @brief Get field uas_id from open_drone_id_basic_id message - * - * @return UAS (Unmanned Aircraft System) ID following the format specified by id_type. Shall be filled with nulls in the unused portion of the field. - */ -static inline uint16_t mavlink_msg_open_drone_id_basic_id_get_uas_id(const mavlink_message_t* msg, uint8_t *uas_id) -{ - return _MAV_RETURN_uint8_t_array(msg, uas_id, 20, 24); -} - -/** - * @brief Decode a open_drone_id_basic_id message into a struct - * - * @param msg The message to decode - * @param open_drone_id_basic_id C-struct to decode the message contents into - */ -static inline void mavlink_msg_open_drone_id_basic_id_decode(const mavlink_message_t* msg, mavlink_open_drone_id_basic_id_t* open_drone_id_basic_id) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - open_drone_id_basic_id->target_system = mavlink_msg_open_drone_id_basic_id_get_target_system(msg); - open_drone_id_basic_id->target_component = mavlink_msg_open_drone_id_basic_id_get_target_component(msg); - mavlink_msg_open_drone_id_basic_id_get_id_or_mac(msg, open_drone_id_basic_id->id_or_mac); - open_drone_id_basic_id->id_type = mavlink_msg_open_drone_id_basic_id_get_id_type(msg); - open_drone_id_basic_id->ua_type = mavlink_msg_open_drone_id_basic_id_get_ua_type(msg); - mavlink_msg_open_drone_id_basic_id_get_uas_id(msg, open_drone_id_basic_id->uas_id); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_OPEN_DRONE_ID_BASIC_ID_LEN? msg->len : MAVLINK_MSG_ID_OPEN_DRONE_ID_BASIC_ID_LEN; - memset(open_drone_id_basic_id, 0, MAVLINK_MSG_ID_OPEN_DRONE_ID_BASIC_ID_LEN); - memcpy(open_drone_id_basic_id, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_open_drone_id_location.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_open_drone_id_location.h deleted file mode 100644 index c0fd46cf..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_open_drone_id_location.h +++ /dev/null @@ -1,655 +0,0 @@ -#pragma once -// MESSAGE OPEN_DRONE_ID_LOCATION PACKING - -#define MAVLINK_MSG_ID_OPEN_DRONE_ID_LOCATION 12901 - - -typedef struct __mavlink_open_drone_id_location_t { - int32_t latitude; /*< [degE7] Current latitude of the unmanned aircraft. If unknown: 0 (both Lat/Lon).*/ - int32_t longitude; /*< [degE7] Current longitude of the unmanned aircraft. If unknown: 0 (both Lat/Lon).*/ - float altitude_barometric; /*< [m] The altitude calculated from the barometric pressue. Reference is against 29.92inHg or 1013.2mb. If unknown: -1000 m.*/ - float altitude_geodetic; /*< [m] The geodetic altitude as defined by WGS84. If unknown: -1000 m.*/ - float height; /*< [m] The current height of the unmanned aircraft above the take-off location or the ground as indicated by height_reference. If unknown: -1000 m.*/ - float timestamp; /*< [s] Seconds after the full hour with reference to UTC time. Typically the GPS outputs a time-of-week value in milliseconds. First convert that to UTC and then convert for this field using ((float) (time_week_ms % (60*60*1000))) / 1000. If unknown: 0xFFFF.*/ - uint16_t direction; /*< [cdeg] Direction over ground (not heading, but direction of movement) measured clockwise from true North: 0 - 35999 centi-degrees. If unknown: 36100 centi-degrees.*/ - uint16_t speed_horizontal; /*< [cm/s] Ground speed. Positive only. If unknown: 25500 cm/s. If speed is larger than 25425 cm/s, use 25425 cm/s.*/ - int16_t speed_vertical; /*< [cm/s] The vertical speed. Up is positive. If unknown: 6300 cm/s. If speed is larger than 6200 cm/s, use 6200 cm/s. If lower than -6200 cm/s, use -6200 cm/s.*/ - uint8_t target_system; /*< System ID (0 for broadcast).*/ - uint8_t target_component; /*< Component ID (0 for broadcast).*/ - uint8_t id_or_mac[20]; /*< Only used for drone ID data received from other UAs. See detailed description at https://mavlink.io/en/services/opendroneid.html. */ - uint8_t status; /*< Indicates whether the unmanned aircraft is on the ground or in the air.*/ - uint8_t height_reference; /*< Indicates the reference point for the height field.*/ - uint8_t horizontal_accuracy; /*< The accuracy of the horizontal position.*/ - uint8_t vertical_accuracy; /*< The accuracy of the vertical position.*/ - uint8_t barometer_accuracy; /*< The accuracy of the barometric altitude.*/ - uint8_t speed_accuracy; /*< The accuracy of the horizontal and vertical speed.*/ - uint8_t timestamp_accuracy; /*< The accuracy of the timestamps.*/ -} mavlink_open_drone_id_location_t; - -#define MAVLINK_MSG_ID_OPEN_DRONE_ID_LOCATION_LEN 59 -#define MAVLINK_MSG_ID_OPEN_DRONE_ID_LOCATION_MIN_LEN 59 -#define MAVLINK_MSG_ID_12901_LEN 59 -#define MAVLINK_MSG_ID_12901_MIN_LEN 59 - -#define MAVLINK_MSG_ID_OPEN_DRONE_ID_LOCATION_CRC 254 -#define MAVLINK_MSG_ID_12901_CRC 254 - -#define MAVLINK_MSG_OPEN_DRONE_ID_LOCATION_FIELD_ID_OR_MAC_LEN 20 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_OPEN_DRONE_ID_LOCATION { \ - 12901, \ - "OPEN_DRONE_ID_LOCATION", \ - 19, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_open_drone_id_location_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_open_drone_id_location_t, target_component) }, \ - { "id_or_mac", NULL, MAVLINK_TYPE_UINT8_T, 20, 32, offsetof(mavlink_open_drone_id_location_t, id_or_mac) }, \ - { "status", NULL, MAVLINK_TYPE_UINT8_T, 0, 52, offsetof(mavlink_open_drone_id_location_t, status) }, \ - { "direction", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_open_drone_id_location_t, direction) }, \ - { "speed_horizontal", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_open_drone_id_location_t, speed_horizontal) }, \ - { "speed_vertical", NULL, MAVLINK_TYPE_INT16_T, 0, 28, offsetof(mavlink_open_drone_id_location_t, speed_vertical) }, \ - { "latitude", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_open_drone_id_location_t, latitude) }, \ - { "longitude", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_open_drone_id_location_t, longitude) }, \ - { "altitude_barometric", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_open_drone_id_location_t, altitude_barometric) }, \ - { "altitude_geodetic", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_open_drone_id_location_t, altitude_geodetic) }, \ - { "height_reference", NULL, MAVLINK_TYPE_UINT8_T, 0, 53, offsetof(mavlink_open_drone_id_location_t, height_reference) }, \ - { "height", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_open_drone_id_location_t, height) }, \ - { "horizontal_accuracy", NULL, MAVLINK_TYPE_UINT8_T, 0, 54, offsetof(mavlink_open_drone_id_location_t, horizontal_accuracy) }, \ - { "vertical_accuracy", NULL, MAVLINK_TYPE_UINT8_T, 0, 55, offsetof(mavlink_open_drone_id_location_t, vertical_accuracy) }, \ - { "barometer_accuracy", NULL, MAVLINK_TYPE_UINT8_T, 0, 56, offsetof(mavlink_open_drone_id_location_t, barometer_accuracy) }, \ - { "speed_accuracy", NULL, MAVLINK_TYPE_UINT8_T, 0, 57, offsetof(mavlink_open_drone_id_location_t, speed_accuracy) }, \ - { "timestamp", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_open_drone_id_location_t, timestamp) }, \ - { "timestamp_accuracy", NULL, MAVLINK_TYPE_UINT8_T, 0, 58, offsetof(mavlink_open_drone_id_location_t, timestamp_accuracy) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_OPEN_DRONE_ID_LOCATION { \ - "OPEN_DRONE_ID_LOCATION", \ - 19, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_open_drone_id_location_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_open_drone_id_location_t, target_component) }, \ - { "id_or_mac", NULL, MAVLINK_TYPE_UINT8_T, 20, 32, offsetof(mavlink_open_drone_id_location_t, id_or_mac) }, \ - { "status", NULL, MAVLINK_TYPE_UINT8_T, 0, 52, offsetof(mavlink_open_drone_id_location_t, status) }, \ - { "direction", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_open_drone_id_location_t, direction) }, \ - { "speed_horizontal", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_open_drone_id_location_t, speed_horizontal) }, \ - { "speed_vertical", NULL, MAVLINK_TYPE_INT16_T, 0, 28, offsetof(mavlink_open_drone_id_location_t, speed_vertical) }, \ - { "latitude", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_open_drone_id_location_t, latitude) }, \ - { "longitude", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_open_drone_id_location_t, longitude) }, \ - { "altitude_barometric", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_open_drone_id_location_t, altitude_barometric) }, \ - { "altitude_geodetic", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_open_drone_id_location_t, altitude_geodetic) }, \ - { "height_reference", NULL, MAVLINK_TYPE_UINT8_T, 0, 53, offsetof(mavlink_open_drone_id_location_t, height_reference) }, \ - { "height", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_open_drone_id_location_t, height) }, \ - { "horizontal_accuracy", NULL, MAVLINK_TYPE_UINT8_T, 0, 54, offsetof(mavlink_open_drone_id_location_t, horizontal_accuracy) }, \ - { "vertical_accuracy", NULL, MAVLINK_TYPE_UINT8_T, 0, 55, offsetof(mavlink_open_drone_id_location_t, vertical_accuracy) }, \ - { "barometer_accuracy", NULL, MAVLINK_TYPE_UINT8_T, 0, 56, offsetof(mavlink_open_drone_id_location_t, barometer_accuracy) }, \ - { "speed_accuracy", NULL, MAVLINK_TYPE_UINT8_T, 0, 57, offsetof(mavlink_open_drone_id_location_t, speed_accuracy) }, \ - { "timestamp", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_open_drone_id_location_t, timestamp) }, \ - { "timestamp_accuracy", NULL, MAVLINK_TYPE_UINT8_T, 0, 58, offsetof(mavlink_open_drone_id_location_t, timestamp_accuracy) }, \ - } \ -} -#endif - -/** - * @brief Pack a open_drone_id_location message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID (0 for broadcast). - * @param target_component Component ID (0 for broadcast). - * @param id_or_mac Only used for drone ID data received from other UAs. See detailed description at https://mavlink.io/en/services/opendroneid.html. - * @param status Indicates whether the unmanned aircraft is on the ground or in the air. - * @param direction [cdeg] Direction over ground (not heading, but direction of movement) measured clockwise from true North: 0 - 35999 centi-degrees. If unknown: 36100 centi-degrees. - * @param speed_horizontal [cm/s] Ground speed. Positive only. If unknown: 25500 cm/s. If speed is larger than 25425 cm/s, use 25425 cm/s. - * @param speed_vertical [cm/s] The vertical speed. Up is positive. If unknown: 6300 cm/s. If speed is larger than 6200 cm/s, use 6200 cm/s. If lower than -6200 cm/s, use -6200 cm/s. - * @param latitude [degE7] Current latitude of the unmanned aircraft. If unknown: 0 (both Lat/Lon). - * @param longitude [degE7] Current longitude of the unmanned aircraft. If unknown: 0 (both Lat/Lon). - * @param altitude_barometric [m] The altitude calculated from the barometric pressue. Reference is against 29.92inHg or 1013.2mb. If unknown: -1000 m. - * @param altitude_geodetic [m] The geodetic altitude as defined by WGS84. If unknown: -1000 m. - * @param height_reference Indicates the reference point for the height field. - * @param height [m] The current height of the unmanned aircraft above the take-off location or the ground as indicated by height_reference. If unknown: -1000 m. - * @param horizontal_accuracy The accuracy of the horizontal position. - * @param vertical_accuracy The accuracy of the vertical position. - * @param barometer_accuracy The accuracy of the barometric altitude. - * @param speed_accuracy The accuracy of the horizontal and vertical speed. - * @param timestamp [s] Seconds after the full hour with reference to UTC time. Typically the GPS outputs a time-of-week value in milliseconds. First convert that to UTC and then convert for this field using ((float) (time_week_ms % (60*60*1000))) / 1000. If unknown: 0xFFFF. - * @param timestamp_accuracy The accuracy of the timestamps. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_open_drone_id_location_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component, const uint8_t *id_or_mac, uint8_t status, uint16_t direction, uint16_t speed_horizontal, int16_t speed_vertical, int32_t latitude, int32_t longitude, float altitude_barometric, float altitude_geodetic, uint8_t height_reference, float height, uint8_t horizontal_accuracy, uint8_t vertical_accuracy, uint8_t barometer_accuracy, uint8_t speed_accuracy, float timestamp, uint8_t timestamp_accuracy) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_OPEN_DRONE_ID_LOCATION_LEN]; - _mav_put_int32_t(buf, 0, latitude); - _mav_put_int32_t(buf, 4, longitude); - _mav_put_float(buf, 8, altitude_barometric); - _mav_put_float(buf, 12, altitude_geodetic); - _mav_put_float(buf, 16, height); - _mav_put_float(buf, 20, timestamp); - _mav_put_uint16_t(buf, 24, direction); - _mav_put_uint16_t(buf, 26, speed_horizontal); - _mav_put_int16_t(buf, 28, speed_vertical); - _mav_put_uint8_t(buf, 30, target_system); - _mav_put_uint8_t(buf, 31, target_component); - _mav_put_uint8_t(buf, 52, status); - _mav_put_uint8_t(buf, 53, height_reference); - _mav_put_uint8_t(buf, 54, horizontal_accuracy); - _mav_put_uint8_t(buf, 55, vertical_accuracy); - _mav_put_uint8_t(buf, 56, barometer_accuracy); - _mav_put_uint8_t(buf, 57, speed_accuracy); - _mav_put_uint8_t(buf, 58, timestamp_accuracy); - _mav_put_uint8_t_array(buf, 32, id_or_mac, 20); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OPEN_DRONE_ID_LOCATION_LEN); -#else - mavlink_open_drone_id_location_t packet; - packet.latitude = latitude; - packet.longitude = longitude; - packet.altitude_barometric = altitude_barometric; - packet.altitude_geodetic = altitude_geodetic; - packet.height = height; - packet.timestamp = timestamp; - packet.direction = direction; - packet.speed_horizontal = speed_horizontal; - packet.speed_vertical = speed_vertical; - packet.target_system = target_system; - packet.target_component = target_component; - packet.status = status; - packet.height_reference = height_reference; - packet.horizontal_accuracy = horizontal_accuracy; - packet.vertical_accuracy = vertical_accuracy; - packet.barometer_accuracy = barometer_accuracy; - packet.speed_accuracy = speed_accuracy; - packet.timestamp_accuracy = timestamp_accuracy; - mav_array_memcpy(packet.id_or_mac, id_or_mac, sizeof(uint8_t)*20); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_OPEN_DRONE_ID_LOCATION_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_OPEN_DRONE_ID_LOCATION; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_OPEN_DRONE_ID_LOCATION_MIN_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_LOCATION_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_LOCATION_CRC); -} - -/** - * @brief Pack a open_drone_id_location message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID (0 for broadcast). - * @param target_component Component ID (0 for broadcast). - * @param id_or_mac Only used for drone ID data received from other UAs. See detailed description at https://mavlink.io/en/services/opendroneid.html. - * @param status Indicates whether the unmanned aircraft is on the ground or in the air. - * @param direction [cdeg] Direction over ground (not heading, but direction of movement) measured clockwise from true North: 0 - 35999 centi-degrees. If unknown: 36100 centi-degrees. - * @param speed_horizontal [cm/s] Ground speed. Positive only. If unknown: 25500 cm/s. If speed is larger than 25425 cm/s, use 25425 cm/s. - * @param speed_vertical [cm/s] The vertical speed. Up is positive. If unknown: 6300 cm/s. If speed is larger than 6200 cm/s, use 6200 cm/s. If lower than -6200 cm/s, use -6200 cm/s. - * @param latitude [degE7] Current latitude of the unmanned aircraft. If unknown: 0 (both Lat/Lon). - * @param longitude [degE7] Current longitude of the unmanned aircraft. If unknown: 0 (both Lat/Lon). - * @param altitude_barometric [m] The altitude calculated from the barometric pressue. Reference is against 29.92inHg or 1013.2mb. If unknown: -1000 m. - * @param altitude_geodetic [m] The geodetic altitude as defined by WGS84. If unknown: -1000 m. - * @param height_reference Indicates the reference point for the height field. - * @param height [m] The current height of the unmanned aircraft above the take-off location or the ground as indicated by height_reference. If unknown: -1000 m. - * @param horizontal_accuracy The accuracy of the horizontal position. - * @param vertical_accuracy The accuracy of the vertical position. - * @param barometer_accuracy The accuracy of the barometric altitude. - * @param speed_accuracy The accuracy of the horizontal and vertical speed. - * @param timestamp [s] Seconds after the full hour with reference to UTC time. Typically the GPS outputs a time-of-week value in milliseconds. First convert that to UTC and then convert for this field using ((float) (time_week_ms % (60*60*1000))) / 1000. If unknown: 0xFFFF. - * @param timestamp_accuracy The accuracy of the timestamps. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_open_drone_id_location_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component,const uint8_t *id_or_mac,uint8_t status,uint16_t direction,uint16_t speed_horizontal,int16_t speed_vertical,int32_t latitude,int32_t longitude,float altitude_barometric,float altitude_geodetic,uint8_t height_reference,float height,uint8_t horizontal_accuracy,uint8_t vertical_accuracy,uint8_t barometer_accuracy,uint8_t speed_accuracy,float timestamp,uint8_t timestamp_accuracy) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_OPEN_DRONE_ID_LOCATION_LEN]; - _mav_put_int32_t(buf, 0, latitude); - _mav_put_int32_t(buf, 4, longitude); - _mav_put_float(buf, 8, altitude_barometric); - _mav_put_float(buf, 12, altitude_geodetic); - _mav_put_float(buf, 16, height); - _mav_put_float(buf, 20, timestamp); - _mav_put_uint16_t(buf, 24, direction); - _mav_put_uint16_t(buf, 26, speed_horizontal); - _mav_put_int16_t(buf, 28, speed_vertical); - _mav_put_uint8_t(buf, 30, target_system); - _mav_put_uint8_t(buf, 31, target_component); - _mav_put_uint8_t(buf, 52, status); - _mav_put_uint8_t(buf, 53, height_reference); - _mav_put_uint8_t(buf, 54, horizontal_accuracy); - _mav_put_uint8_t(buf, 55, vertical_accuracy); - _mav_put_uint8_t(buf, 56, barometer_accuracy); - _mav_put_uint8_t(buf, 57, speed_accuracy); - _mav_put_uint8_t(buf, 58, timestamp_accuracy); - _mav_put_uint8_t_array(buf, 32, id_or_mac, 20); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OPEN_DRONE_ID_LOCATION_LEN); -#else - mavlink_open_drone_id_location_t packet; - packet.latitude = latitude; - packet.longitude = longitude; - packet.altitude_barometric = altitude_barometric; - packet.altitude_geodetic = altitude_geodetic; - packet.height = height; - packet.timestamp = timestamp; - packet.direction = direction; - packet.speed_horizontal = speed_horizontal; - packet.speed_vertical = speed_vertical; - packet.target_system = target_system; - packet.target_component = target_component; - packet.status = status; - packet.height_reference = height_reference; - packet.horizontal_accuracy = horizontal_accuracy; - packet.vertical_accuracy = vertical_accuracy; - packet.barometer_accuracy = barometer_accuracy; - packet.speed_accuracy = speed_accuracy; - packet.timestamp_accuracy = timestamp_accuracy; - mav_array_memcpy(packet.id_or_mac, id_or_mac, sizeof(uint8_t)*20); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_OPEN_DRONE_ID_LOCATION_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_OPEN_DRONE_ID_LOCATION; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_OPEN_DRONE_ID_LOCATION_MIN_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_LOCATION_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_LOCATION_CRC); -} - -/** - * @brief Encode a open_drone_id_location struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param open_drone_id_location C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_open_drone_id_location_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_open_drone_id_location_t* open_drone_id_location) -{ - return mavlink_msg_open_drone_id_location_pack(system_id, component_id, msg, open_drone_id_location->target_system, open_drone_id_location->target_component, open_drone_id_location->id_or_mac, open_drone_id_location->status, open_drone_id_location->direction, open_drone_id_location->speed_horizontal, open_drone_id_location->speed_vertical, open_drone_id_location->latitude, open_drone_id_location->longitude, open_drone_id_location->altitude_barometric, open_drone_id_location->altitude_geodetic, open_drone_id_location->height_reference, open_drone_id_location->height, open_drone_id_location->horizontal_accuracy, open_drone_id_location->vertical_accuracy, open_drone_id_location->barometer_accuracy, open_drone_id_location->speed_accuracy, open_drone_id_location->timestamp, open_drone_id_location->timestamp_accuracy); -} - -/** - * @brief Encode a open_drone_id_location struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param open_drone_id_location C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_open_drone_id_location_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_open_drone_id_location_t* open_drone_id_location) -{ - return mavlink_msg_open_drone_id_location_pack_chan(system_id, component_id, chan, msg, open_drone_id_location->target_system, open_drone_id_location->target_component, open_drone_id_location->id_or_mac, open_drone_id_location->status, open_drone_id_location->direction, open_drone_id_location->speed_horizontal, open_drone_id_location->speed_vertical, open_drone_id_location->latitude, open_drone_id_location->longitude, open_drone_id_location->altitude_barometric, open_drone_id_location->altitude_geodetic, open_drone_id_location->height_reference, open_drone_id_location->height, open_drone_id_location->horizontal_accuracy, open_drone_id_location->vertical_accuracy, open_drone_id_location->barometer_accuracy, open_drone_id_location->speed_accuracy, open_drone_id_location->timestamp, open_drone_id_location->timestamp_accuracy); -} - -/** - * @brief Send a open_drone_id_location message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID (0 for broadcast). - * @param target_component Component ID (0 for broadcast). - * @param id_or_mac Only used for drone ID data received from other UAs. See detailed description at https://mavlink.io/en/services/opendroneid.html. - * @param status Indicates whether the unmanned aircraft is on the ground or in the air. - * @param direction [cdeg] Direction over ground (not heading, but direction of movement) measured clockwise from true North: 0 - 35999 centi-degrees. If unknown: 36100 centi-degrees. - * @param speed_horizontal [cm/s] Ground speed. Positive only. If unknown: 25500 cm/s. If speed is larger than 25425 cm/s, use 25425 cm/s. - * @param speed_vertical [cm/s] The vertical speed. Up is positive. If unknown: 6300 cm/s. If speed is larger than 6200 cm/s, use 6200 cm/s. If lower than -6200 cm/s, use -6200 cm/s. - * @param latitude [degE7] Current latitude of the unmanned aircraft. If unknown: 0 (both Lat/Lon). - * @param longitude [degE7] Current longitude of the unmanned aircraft. If unknown: 0 (both Lat/Lon). - * @param altitude_barometric [m] The altitude calculated from the barometric pressue. Reference is against 29.92inHg or 1013.2mb. If unknown: -1000 m. - * @param altitude_geodetic [m] The geodetic altitude as defined by WGS84. If unknown: -1000 m. - * @param height_reference Indicates the reference point for the height field. - * @param height [m] The current height of the unmanned aircraft above the take-off location or the ground as indicated by height_reference. If unknown: -1000 m. - * @param horizontal_accuracy The accuracy of the horizontal position. - * @param vertical_accuracy The accuracy of the vertical position. - * @param barometer_accuracy The accuracy of the barometric altitude. - * @param speed_accuracy The accuracy of the horizontal and vertical speed. - * @param timestamp [s] Seconds after the full hour with reference to UTC time. Typically the GPS outputs a time-of-week value in milliseconds. First convert that to UTC and then convert for this field using ((float) (time_week_ms % (60*60*1000))) / 1000. If unknown: 0xFFFF. - * @param timestamp_accuracy The accuracy of the timestamps. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_open_drone_id_location_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, const uint8_t *id_or_mac, uint8_t status, uint16_t direction, uint16_t speed_horizontal, int16_t speed_vertical, int32_t latitude, int32_t longitude, float altitude_barometric, float altitude_geodetic, uint8_t height_reference, float height, uint8_t horizontal_accuracy, uint8_t vertical_accuracy, uint8_t barometer_accuracy, uint8_t speed_accuracy, float timestamp, uint8_t timestamp_accuracy) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_OPEN_DRONE_ID_LOCATION_LEN]; - _mav_put_int32_t(buf, 0, latitude); - _mav_put_int32_t(buf, 4, longitude); - _mav_put_float(buf, 8, altitude_barometric); - _mav_put_float(buf, 12, altitude_geodetic); - _mav_put_float(buf, 16, height); - _mav_put_float(buf, 20, timestamp); - _mav_put_uint16_t(buf, 24, direction); - _mav_put_uint16_t(buf, 26, speed_horizontal); - _mav_put_int16_t(buf, 28, speed_vertical); - _mav_put_uint8_t(buf, 30, target_system); - _mav_put_uint8_t(buf, 31, target_component); - _mav_put_uint8_t(buf, 52, status); - _mav_put_uint8_t(buf, 53, height_reference); - _mav_put_uint8_t(buf, 54, horizontal_accuracy); - _mav_put_uint8_t(buf, 55, vertical_accuracy); - _mav_put_uint8_t(buf, 56, barometer_accuracy); - _mav_put_uint8_t(buf, 57, speed_accuracy); - _mav_put_uint8_t(buf, 58, timestamp_accuracy); - _mav_put_uint8_t_array(buf, 32, id_or_mac, 20); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPEN_DRONE_ID_LOCATION, buf, MAVLINK_MSG_ID_OPEN_DRONE_ID_LOCATION_MIN_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_LOCATION_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_LOCATION_CRC); -#else - mavlink_open_drone_id_location_t packet; - packet.latitude = latitude; - packet.longitude = longitude; - packet.altitude_barometric = altitude_barometric; - packet.altitude_geodetic = altitude_geodetic; - packet.height = height; - packet.timestamp = timestamp; - packet.direction = direction; - packet.speed_horizontal = speed_horizontal; - packet.speed_vertical = speed_vertical; - packet.target_system = target_system; - packet.target_component = target_component; - packet.status = status; - packet.height_reference = height_reference; - packet.horizontal_accuracy = horizontal_accuracy; - packet.vertical_accuracy = vertical_accuracy; - packet.barometer_accuracy = barometer_accuracy; - packet.speed_accuracy = speed_accuracy; - packet.timestamp_accuracy = timestamp_accuracy; - mav_array_memcpy(packet.id_or_mac, id_or_mac, sizeof(uint8_t)*20); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPEN_DRONE_ID_LOCATION, (const char *)&packet, MAVLINK_MSG_ID_OPEN_DRONE_ID_LOCATION_MIN_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_LOCATION_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_LOCATION_CRC); -#endif -} - -/** - * @brief Send a open_drone_id_location message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_open_drone_id_location_send_struct(mavlink_channel_t chan, const mavlink_open_drone_id_location_t* open_drone_id_location) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_open_drone_id_location_send(chan, open_drone_id_location->target_system, open_drone_id_location->target_component, open_drone_id_location->id_or_mac, open_drone_id_location->status, open_drone_id_location->direction, open_drone_id_location->speed_horizontal, open_drone_id_location->speed_vertical, open_drone_id_location->latitude, open_drone_id_location->longitude, open_drone_id_location->altitude_barometric, open_drone_id_location->altitude_geodetic, open_drone_id_location->height_reference, open_drone_id_location->height, open_drone_id_location->horizontal_accuracy, open_drone_id_location->vertical_accuracy, open_drone_id_location->barometer_accuracy, open_drone_id_location->speed_accuracy, open_drone_id_location->timestamp, open_drone_id_location->timestamp_accuracy); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPEN_DRONE_ID_LOCATION, (const char *)open_drone_id_location, MAVLINK_MSG_ID_OPEN_DRONE_ID_LOCATION_MIN_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_LOCATION_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_LOCATION_CRC); -#endif -} - -#if MAVLINK_MSG_ID_OPEN_DRONE_ID_LOCATION_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_open_drone_id_location_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, const uint8_t *id_or_mac, uint8_t status, uint16_t direction, uint16_t speed_horizontal, int16_t speed_vertical, int32_t latitude, int32_t longitude, float altitude_barometric, float altitude_geodetic, uint8_t height_reference, float height, uint8_t horizontal_accuracy, uint8_t vertical_accuracy, uint8_t barometer_accuracy, uint8_t speed_accuracy, float timestamp, uint8_t timestamp_accuracy) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_int32_t(buf, 0, latitude); - _mav_put_int32_t(buf, 4, longitude); - _mav_put_float(buf, 8, altitude_barometric); - _mav_put_float(buf, 12, altitude_geodetic); - _mav_put_float(buf, 16, height); - _mav_put_float(buf, 20, timestamp); - _mav_put_uint16_t(buf, 24, direction); - _mav_put_uint16_t(buf, 26, speed_horizontal); - _mav_put_int16_t(buf, 28, speed_vertical); - _mav_put_uint8_t(buf, 30, target_system); - _mav_put_uint8_t(buf, 31, target_component); - _mav_put_uint8_t(buf, 52, status); - _mav_put_uint8_t(buf, 53, height_reference); - _mav_put_uint8_t(buf, 54, horizontal_accuracy); - _mav_put_uint8_t(buf, 55, vertical_accuracy); - _mav_put_uint8_t(buf, 56, barometer_accuracy); - _mav_put_uint8_t(buf, 57, speed_accuracy); - _mav_put_uint8_t(buf, 58, timestamp_accuracy); - _mav_put_uint8_t_array(buf, 32, id_or_mac, 20); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPEN_DRONE_ID_LOCATION, buf, MAVLINK_MSG_ID_OPEN_DRONE_ID_LOCATION_MIN_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_LOCATION_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_LOCATION_CRC); -#else - mavlink_open_drone_id_location_t *packet = (mavlink_open_drone_id_location_t *)msgbuf; - packet->latitude = latitude; - packet->longitude = longitude; - packet->altitude_barometric = altitude_barometric; - packet->altitude_geodetic = altitude_geodetic; - packet->height = height; - packet->timestamp = timestamp; - packet->direction = direction; - packet->speed_horizontal = speed_horizontal; - packet->speed_vertical = speed_vertical; - packet->target_system = target_system; - packet->target_component = target_component; - packet->status = status; - packet->height_reference = height_reference; - packet->horizontal_accuracy = horizontal_accuracy; - packet->vertical_accuracy = vertical_accuracy; - packet->barometer_accuracy = barometer_accuracy; - packet->speed_accuracy = speed_accuracy; - packet->timestamp_accuracy = timestamp_accuracy; - mav_array_memcpy(packet->id_or_mac, id_or_mac, sizeof(uint8_t)*20); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPEN_DRONE_ID_LOCATION, (const char *)packet, MAVLINK_MSG_ID_OPEN_DRONE_ID_LOCATION_MIN_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_LOCATION_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_LOCATION_CRC); -#endif -} -#endif - -#endif - -// MESSAGE OPEN_DRONE_ID_LOCATION UNPACKING - - -/** - * @brief Get field target_system from open_drone_id_location message - * - * @return System ID (0 for broadcast). - */ -static inline uint8_t mavlink_msg_open_drone_id_location_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 30); -} - -/** - * @brief Get field target_component from open_drone_id_location message - * - * @return Component ID (0 for broadcast). - */ -static inline uint8_t mavlink_msg_open_drone_id_location_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 31); -} - -/** - * @brief Get field id_or_mac from open_drone_id_location message - * - * @return Only used for drone ID data received from other UAs. See detailed description at https://mavlink.io/en/services/opendroneid.html. - */ -static inline uint16_t mavlink_msg_open_drone_id_location_get_id_or_mac(const mavlink_message_t* msg, uint8_t *id_or_mac) -{ - return _MAV_RETURN_uint8_t_array(msg, id_or_mac, 20, 32); -} - -/** - * @brief Get field status from open_drone_id_location message - * - * @return Indicates whether the unmanned aircraft is on the ground or in the air. - */ -static inline uint8_t mavlink_msg_open_drone_id_location_get_status(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 52); -} - -/** - * @brief Get field direction from open_drone_id_location message - * - * @return [cdeg] Direction over ground (not heading, but direction of movement) measured clockwise from true North: 0 - 35999 centi-degrees. If unknown: 36100 centi-degrees. - */ -static inline uint16_t mavlink_msg_open_drone_id_location_get_direction(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 24); -} - -/** - * @brief Get field speed_horizontal from open_drone_id_location message - * - * @return [cm/s] Ground speed. Positive only. If unknown: 25500 cm/s. If speed is larger than 25425 cm/s, use 25425 cm/s. - */ -static inline uint16_t mavlink_msg_open_drone_id_location_get_speed_horizontal(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 26); -} - -/** - * @brief Get field speed_vertical from open_drone_id_location message - * - * @return [cm/s] The vertical speed. Up is positive. If unknown: 6300 cm/s. If speed is larger than 6200 cm/s, use 6200 cm/s. If lower than -6200 cm/s, use -6200 cm/s. - */ -static inline int16_t mavlink_msg_open_drone_id_location_get_speed_vertical(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 28); -} - -/** - * @brief Get field latitude from open_drone_id_location message - * - * @return [degE7] Current latitude of the unmanned aircraft. If unknown: 0 (both Lat/Lon). - */ -static inline int32_t mavlink_msg_open_drone_id_location_get_latitude(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 0); -} - -/** - * @brief Get field longitude from open_drone_id_location message - * - * @return [degE7] Current longitude of the unmanned aircraft. If unknown: 0 (both Lat/Lon). - */ -static inline int32_t mavlink_msg_open_drone_id_location_get_longitude(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 4); -} - -/** - * @brief Get field altitude_barometric from open_drone_id_location message - * - * @return [m] The altitude calculated from the barometric pressue. Reference is against 29.92inHg or 1013.2mb. If unknown: -1000 m. - */ -static inline float mavlink_msg_open_drone_id_location_get_altitude_barometric(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field altitude_geodetic from open_drone_id_location message - * - * @return [m] The geodetic altitude as defined by WGS84. If unknown: -1000 m. - */ -static inline float mavlink_msg_open_drone_id_location_get_altitude_geodetic(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field height_reference from open_drone_id_location message - * - * @return Indicates the reference point for the height field. - */ -static inline uint8_t mavlink_msg_open_drone_id_location_get_height_reference(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 53); -} - -/** - * @brief Get field height from open_drone_id_location message - * - * @return [m] The current height of the unmanned aircraft above the take-off location or the ground as indicated by height_reference. If unknown: -1000 m. - */ -static inline float mavlink_msg_open_drone_id_location_get_height(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field horizontal_accuracy from open_drone_id_location message - * - * @return The accuracy of the horizontal position. - */ -static inline uint8_t mavlink_msg_open_drone_id_location_get_horizontal_accuracy(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 54); -} - -/** - * @brief Get field vertical_accuracy from open_drone_id_location message - * - * @return The accuracy of the vertical position. - */ -static inline uint8_t mavlink_msg_open_drone_id_location_get_vertical_accuracy(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 55); -} - -/** - * @brief Get field barometer_accuracy from open_drone_id_location message - * - * @return The accuracy of the barometric altitude. - */ -static inline uint8_t mavlink_msg_open_drone_id_location_get_barometer_accuracy(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 56); -} - -/** - * @brief Get field speed_accuracy from open_drone_id_location message - * - * @return The accuracy of the horizontal and vertical speed. - */ -static inline uint8_t mavlink_msg_open_drone_id_location_get_speed_accuracy(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 57); -} - -/** - * @brief Get field timestamp from open_drone_id_location message - * - * @return [s] Seconds after the full hour with reference to UTC time. Typically the GPS outputs a time-of-week value in milliseconds. First convert that to UTC and then convert for this field using ((float) (time_week_ms % (60*60*1000))) / 1000. If unknown: 0xFFFF. - */ -static inline float mavlink_msg_open_drone_id_location_get_timestamp(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Get field timestamp_accuracy from open_drone_id_location message - * - * @return The accuracy of the timestamps. - */ -static inline uint8_t mavlink_msg_open_drone_id_location_get_timestamp_accuracy(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 58); -} - -/** - * @brief Decode a open_drone_id_location message into a struct - * - * @param msg The message to decode - * @param open_drone_id_location C-struct to decode the message contents into - */ -static inline void mavlink_msg_open_drone_id_location_decode(const mavlink_message_t* msg, mavlink_open_drone_id_location_t* open_drone_id_location) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - open_drone_id_location->latitude = mavlink_msg_open_drone_id_location_get_latitude(msg); - open_drone_id_location->longitude = mavlink_msg_open_drone_id_location_get_longitude(msg); - open_drone_id_location->altitude_barometric = mavlink_msg_open_drone_id_location_get_altitude_barometric(msg); - open_drone_id_location->altitude_geodetic = mavlink_msg_open_drone_id_location_get_altitude_geodetic(msg); - open_drone_id_location->height = mavlink_msg_open_drone_id_location_get_height(msg); - open_drone_id_location->timestamp = mavlink_msg_open_drone_id_location_get_timestamp(msg); - open_drone_id_location->direction = mavlink_msg_open_drone_id_location_get_direction(msg); - open_drone_id_location->speed_horizontal = mavlink_msg_open_drone_id_location_get_speed_horizontal(msg); - open_drone_id_location->speed_vertical = mavlink_msg_open_drone_id_location_get_speed_vertical(msg); - open_drone_id_location->target_system = mavlink_msg_open_drone_id_location_get_target_system(msg); - open_drone_id_location->target_component = mavlink_msg_open_drone_id_location_get_target_component(msg); - mavlink_msg_open_drone_id_location_get_id_or_mac(msg, open_drone_id_location->id_or_mac); - open_drone_id_location->status = mavlink_msg_open_drone_id_location_get_status(msg); - open_drone_id_location->height_reference = mavlink_msg_open_drone_id_location_get_height_reference(msg); - open_drone_id_location->horizontal_accuracy = mavlink_msg_open_drone_id_location_get_horizontal_accuracy(msg); - open_drone_id_location->vertical_accuracy = mavlink_msg_open_drone_id_location_get_vertical_accuracy(msg); - open_drone_id_location->barometer_accuracy = mavlink_msg_open_drone_id_location_get_barometer_accuracy(msg); - open_drone_id_location->speed_accuracy = mavlink_msg_open_drone_id_location_get_speed_accuracy(msg); - open_drone_id_location->timestamp_accuracy = mavlink_msg_open_drone_id_location_get_timestamp_accuracy(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_OPEN_DRONE_ID_LOCATION_LEN? msg->len : MAVLINK_MSG_ID_OPEN_DRONE_ID_LOCATION_LEN; - memset(open_drone_id_location, 0, MAVLINK_MSG_ID_OPEN_DRONE_ID_LOCATION_LEN); - memcpy(open_drone_id_location, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_open_drone_id_message_pack.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_open_drone_id_message_pack.h deleted file mode 100644 index 506e3e79..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_open_drone_id_message_pack.h +++ /dev/null @@ -1,331 +0,0 @@ -#pragma once -// MESSAGE OPEN_DRONE_ID_MESSAGE_PACK PACKING - -#define MAVLINK_MSG_ID_OPEN_DRONE_ID_MESSAGE_PACK 12915 - - -typedef struct __mavlink_open_drone_id_message_pack_t { - uint8_t target_system; /*< System ID (0 for broadcast).*/ - uint8_t target_component; /*< Component ID (0 for broadcast).*/ - uint8_t id_or_mac[20]; /*< Only used for drone ID data received from other UAs. See detailed description at https://mavlink.io/en/services/opendroneid.html. */ - uint8_t single_message_size; /*< [bytes] This field must currently always be equal to 25 (bytes), since all encoded OpenDroneID messages are specified to have this length.*/ - uint8_t msg_pack_size; /*< Number of encoded messages in the pack (not the number of bytes). Allowed range is 1 - 9.*/ - uint8_t messages[225]; /*< Concatenation of encoded OpenDroneID messages. Shall be filled with nulls in the unused portion of the field.*/ -} mavlink_open_drone_id_message_pack_t; - -#define MAVLINK_MSG_ID_OPEN_DRONE_ID_MESSAGE_PACK_LEN 249 -#define MAVLINK_MSG_ID_OPEN_DRONE_ID_MESSAGE_PACK_MIN_LEN 249 -#define MAVLINK_MSG_ID_12915_LEN 249 -#define MAVLINK_MSG_ID_12915_MIN_LEN 249 - -#define MAVLINK_MSG_ID_OPEN_DRONE_ID_MESSAGE_PACK_CRC 94 -#define MAVLINK_MSG_ID_12915_CRC 94 - -#define MAVLINK_MSG_OPEN_DRONE_ID_MESSAGE_PACK_FIELD_ID_OR_MAC_LEN 20 -#define MAVLINK_MSG_OPEN_DRONE_ID_MESSAGE_PACK_FIELD_MESSAGES_LEN 225 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_OPEN_DRONE_ID_MESSAGE_PACK { \ - 12915, \ - "OPEN_DRONE_ID_MESSAGE_PACK", \ - 6, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_open_drone_id_message_pack_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_open_drone_id_message_pack_t, target_component) }, \ - { "id_or_mac", NULL, MAVLINK_TYPE_UINT8_T, 20, 2, offsetof(mavlink_open_drone_id_message_pack_t, id_or_mac) }, \ - { "single_message_size", NULL, MAVLINK_TYPE_UINT8_T, 0, 22, offsetof(mavlink_open_drone_id_message_pack_t, single_message_size) }, \ - { "msg_pack_size", NULL, MAVLINK_TYPE_UINT8_T, 0, 23, offsetof(mavlink_open_drone_id_message_pack_t, msg_pack_size) }, \ - { "messages", NULL, MAVLINK_TYPE_UINT8_T, 225, 24, offsetof(mavlink_open_drone_id_message_pack_t, messages) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_OPEN_DRONE_ID_MESSAGE_PACK { \ - "OPEN_DRONE_ID_MESSAGE_PACK", \ - 6, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_open_drone_id_message_pack_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_open_drone_id_message_pack_t, target_component) }, \ - { "id_or_mac", NULL, MAVLINK_TYPE_UINT8_T, 20, 2, offsetof(mavlink_open_drone_id_message_pack_t, id_or_mac) }, \ - { "single_message_size", NULL, MAVLINK_TYPE_UINT8_T, 0, 22, offsetof(mavlink_open_drone_id_message_pack_t, single_message_size) }, \ - { "msg_pack_size", NULL, MAVLINK_TYPE_UINT8_T, 0, 23, offsetof(mavlink_open_drone_id_message_pack_t, msg_pack_size) }, \ - { "messages", NULL, MAVLINK_TYPE_UINT8_T, 225, 24, offsetof(mavlink_open_drone_id_message_pack_t, messages) }, \ - } \ -} -#endif - -/** - * @brief Pack a open_drone_id_message_pack message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID (0 for broadcast). - * @param target_component Component ID (0 for broadcast). - * @param id_or_mac Only used for drone ID data received from other UAs. See detailed description at https://mavlink.io/en/services/opendroneid.html. - * @param single_message_size [bytes] This field must currently always be equal to 25 (bytes), since all encoded OpenDroneID messages are specified to have this length. - * @param msg_pack_size Number of encoded messages in the pack (not the number of bytes). Allowed range is 1 - 9. - * @param messages Concatenation of encoded OpenDroneID messages. Shall be filled with nulls in the unused portion of the field. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_open_drone_id_message_pack_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component, const uint8_t *id_or_mac, uint8_t single_message_size, uint8_t msg_pack_size, const uint8_t *messages) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_OPEN_DRONE_ID_MESSAGE_PACK_LEN]; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - _mav_put_uint8_t(buf, 22, single_message_size); - _mav_put_uint8_t(buf, 23, msg_pack_size); - _mav_put_uint8_t_array(buf, 2, id_or_mac, 20); - _mav_put_uint8_t_array(buf, 24, messages, 225); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OPEN_DRONE_ID_MESSAGE_PACK_LEN); -#else - mavlink_open_drone_id_message_pack_t packet; - packet.target_system = target_system; - packet.target_component = target_component; - packet.single_message_size = single_message_size; - packet.msg_pack_size = msg_pack_size; - mav_array_memcpy(packet.id_or_mac, id_or_mac, sizeof(uint8_t)*20); - mav_array_memcpy(packet.messages, messages, sizeof(uint8_t)*225); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_OPEN_DRONE_ID_MESSAGE_PACK_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_OPEN_DRONE_ID_MESSAGE_PACK; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_OPEN_DRONE_ID_MESSAGE_PACK_MIN_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_MESSAGE_PACK_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_MESSAGE_PACK_CRC); -} - -/** - * @brief Pack a open_drone_id_message_pack message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID (0 for broadcast). - * @param target_component Component ID (0 for broadcast). - * @param id_or_mac Only used for drone ID data received from other UAs. See detailed description at https://mavlink.io/en/services/opendroneid.html. - * @param single_message_size [bytes] This field must currently always be equal to 25 (bytes), since all encoded OpenDroneID messages are specified to have this length. - * @param msg_pack_size Number of encoded messages in the pack (not the number of bytes). Allowed range is 1 - 9. - * @param messages Concatenation of encoded OpenDroneID messages. Shall be filled with nulls in the unused portion of the field. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_open_drone_id_message_pack_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component,const uint8_t *id_or_mac,uint8_t single_message_size,uint8_t msg_pack_size,const uint8_t *messages) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_OPEN_DRONE_ID_MESSAGE_PACK_LEN]; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - _mav_put_uint8_t(buf, 22, single_message_size); - _mav_put_uint8_t(buf, 23, msg_pack_size); - _mav_put_uint8_t_array(buf, 2, id_or_mac, 20); - _mav_put_uint8_t_array(buf, 24, messages, 225); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OPEN_DRONE_ID_MESSAGE_PACK_LEN); -#else - mavlink_open_drone_id_message_pack_t packet; - packet.target_system = target_system; - packet.target_component = target_component; - packet.single_message_size = single_message_size; - packet.msg_pack_size = msg_pack_size; - mav_array_memcpy(packet.id_or_mac, id_or_mac, sizeof(uint8_t)*20); - mav_array_memcpy(packet.messages, messages, sizeof(uint8_t)*225); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_OPEN_DRONE_ID_MESSAGE_PACK_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_OPEN_DRONE_ID_MESSAGE_PACK; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_OPEN_DRONE_ID_MESSAGE_PACK_MIN_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_MESSAGE_PACK_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_MESSAGE_PACK_CRC); -} - -/** - * @brief Encode a open_drone_id_message_pack struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param open_drone_id_message_pack C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_open_drone_id_message_pack_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_open_drone_id_message_pack_t* open_drone_id_message_pack) -{ - return mavlink_msg_open_drone_id_message_pack_pack(system_id, component_id, msg, open_drone_id_message_pack->target_system, open_drone_id_message_pack->target_component, open_drone_id_message_pack->id_or_mac, open_drone_id_message_pack->single_message_size, open_drone_id_message_pack->msg_pack_size, open_drone_id_message_pack->messages); -} - -/** - * @brief Encode a open_drone_id_message_pack struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param open_drone_id_message_pack C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_open_drone_id_message_pack_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_open_drone_id_message_pack_t* open_drone_id_message_pack) -{ - return mavlink_msg_open_drone_id_message_pack_pack_chan(system_id, component_id, chan, msg, open_drone_id_message_pack->target_system, open_drone_id_message_pack->target_component, open_drone_id_message_pack->id_or_mac, open_drone_id_message_pack->single_message_size, open_drone_id_message_pack->msg_pack_size, open_drone_id_message_pack->messages); -} - -/** - * @brief Send a open_drone_id_message_pack message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID (0 for broadcast). - * @param target_component Component ID (0 for broadcast). - * @param id_or_mac Only used for drone ID data received from other UAs. See detailed description at https://mavlink.io/en/services/opendroneid.html. - * @param single_message_size [bytes] This field must currently always be equal to 25 (bytes), since all encoded OpenDroneID messages are specified to have this length. - * @param msg_pack_size Number of encoded messages in the pack (not the number of bytes). Allowed range is 1 - 9. - * @param messages Concatenation of encoded OpenDroneID messages. Shall be filled with nulls in the unused portion of the field. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_open_drone_id_message_pack_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, const uint8_t *id_or_mac, uint8_t single_message_size, uint8_t msg_pack_size, const uint8_t *messages) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_OPEN_DRONE_ID_MESSAGE_PACK_LEN]; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - _mav_put_uint8_t(buf, 22, single_message_size); - _mav_put_uint8_t(buf, 23, msg_pack_size); - _mav_put_uint8_t_array(buf, 2, id_or_mac, 20); - _mav_put_uint8_t_array(buf, 24, messages, 225); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPEN_DRONE_ID_MESSAGE_PACK, buf, MAVLINK_MSG_ID_OPEN_DRONE_ID_MESSAGE_PACK_MIN_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_MESSAGE_PACK_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_MESSAGE_PACK_CRC); -#else - mavlink_open_drone_id_message_pack_t packet; - packet.target_system = target_system; - packet.target_component = target_component; - packet.single_message_size = single_message_size; - packet.msg_pack_size = msg_pack_size; - mav_array_memcpy(packet.id_or_mac, id_or_mac, sizeof(uint8_t)*20); - mav_array_memcpy(packet.messages, messages, sizeof(uint8_t)*225); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPEN_DRONE_ID_MESSAGE_PACK, (const char *)&packet, MAVLINK_MSG_ID_OPEN_DRONE_ID_MESSAGE_PACK_MIN_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_MESSAGE_PACK_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_MESSAGE_PACK_CRC); -#endif -} - -/** - * @brief Send a open_drone_id_message_pack message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_open_drone_id_message_pack_send_struct(mavlink_channel_t chan, const mavlink_open_drone_id_message_pack_t* open_drone_id_message_pack) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_open_drone_id_message_pack_send(chan, open_drone_id_message_pack->target_system, open_drone_id_message_pack->target_component, open_drone_id_message_pack->id_or_mac, open_drone_id_message_pack->single_message_size, open_drone_id_message_pack->msg_pack_size, open_drone_id_message_pack->messages); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPEN_DRONE_ID_MESSAGE_PACK, (const char *)open_drone_id_message_pack, MAVLINK_MSG_ID_OPEN_DRONE_ID_MESSAGE_PACK_MIN_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_MESSAGE_PACK_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_MESSAGE_PACK_CRC); -#endif -} - -#if MAVLINK_MSG_ID_OPEN_DRONE_ID_MESSAGE_PACK_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_open_drone_id_message_pack_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, const uint8_t *id_or_mac, uint8_t single_message_size, uint8_t msg_pack_size, const uint8_t *messages) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - _mav_put_uint8_t(buf, 22, single_message_size); - _mav_put_uint8_t(buf, 23, msg_pack_size); - _mav_put_uint8_t_array(buf, 2, id_or_mac, 20); - _mav_put_uint8_t_array(buf, 24, messages, 225); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPEN_DRONE_ID_MESSAGE_PACK, buf, MAVLINK_MSG_ID_OPEN_DRONE_ID_MESSAGE_PACK_MIN_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_MESSAGE_PACK_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_MESSAGE_PACK_CRC); -#else - mavlink_open_drone_id_message_pack_t *packet = (mavlink_open_drone_id_message_pack_t *)msgbuf; - packet->target_system = target_system; - packet->target_component = target_component; - packet->single_message_size = single_message_size; - packet->msg_pack_size = msg_pack_size; - mav_array_memcpy(packet->id_or_mac, id_or_mac, sizeof(uint8_t)*20); - mav_array_memcpy(packet->messages, messages, sizeof(uint8_t)*225); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPEN_DRONE_ID_MESSAGE_PACK, (const char *)packet, MAVLINK_MSG_ID_OPEN_DRONE_ID_MESSAGE_PACK_MIN_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_MESSAGE_PACK_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_MESSAGE_PACK_CRC); -#endif -} -#endif - -#endif - -// MESSAGE OPEN_DRONE_ID_MESSAGE_PACK UNPACKING - - -/** - * @brief Get field target_system from open_drone_id_message_pack message - * - * @return System ID (0 for broadcast). - */ -static inline uint8_t mavlink_msg_open_drone_id_message_pack_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 0); -} - -/** - * @brief Get field target_component from open_drone_id_message_pack message - * - * @return Component ID (0 for broadcast). - */ -static inline uint8_t mavlink_msg_open_drone_id_message_pack_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 1); -} - -/** - * @brief Get field id_or_mac from open_drone_id_message_pack message - * - * @return Only used for drone ID data received from other UAs. See detailed description at https://mavlink.io/en/services/opendroneid.html. - */ -static inline uint16_t mavlink_msg_open_drone_id_message_pack_get_id_or_mac(const mavlink_message_t* msg, uint8_t *id_or_mac) -{ - return _MAV_RETURN_uint8_t_array(msg, id_or_mac, 20, 2); -} - -/** - * @brief Get field single_message_size from open_drone_id_message_pack message - * - * @return [bytes] This field must currently always be equal to 25 (bytes), since all encoded OpenDroneID messages are specified to have this length. - */ -static inline uint8_t mavlink_msg_open_drone_id_message_pack_get_single_message_size(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 22); -} - -/** - * @brief Get field msg_pack_size from open_drone_id_message_pack message - * - * @return Number of encoded messages in the pack (not the number of bytes). Allowed range is 1 - 9. - */ -static inline uint8_t mavlink_msg_open_drone_id_message_pack_get_msg_pack_size(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 23); -} - -/** - * @brief Get field messages from open_drone_id_message_pack message - * - * @return Concatenation of encoded OpenDroneID messages. Shall be filled with nulls in the unused portion of the field. - */ -static inline uint16_t mavlink_msg_open_drone_id_message_pack_get_messages(const mavlink_message_t* msg, uint8_t *messages) -{ - return _MAV_RETURN_uint8_t_array(msg, messages, 225, 24); -} - -/** - * @brief Decode a open_drone_id_message_pack message into a struct - * - * @param msg The message to decode - * @param open_drone_id_message_pack C-struct to decode the message contents into - */ -static inline void mavlink_msg_open_drone_id_message_pack_decode(const mavlink_message_t* msg, mavlink_open_drone_id_message_pack_t* open_drone_id_message_pack) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - open_drone_id_message_pack->target_system = mavlink_msg_open_drone_id_message_pack_get_target_system(msg); - open_drone_id_message_pack->target_component = mavlink_msg_open_drone_id_message_pack_get_target_component(msg); - mavlink_msg_open_drone_id_message_pack_get_id_or_mac(msg, open_drone_id_message_pack->id_or_mac); - open_drone_id_message_pack->single_message_size = mavlink_msg_open_drone_id_message_pack_get_single_message_size(msg); - open_drone_id_message_pack->msg_pack_size = mavlink_msg_open_drone_id_message_pack_get_msg_pack_size(msg); - mavlink_msg_open_drone_id_message_pack_get_messages(msg, open_drone_id_message_pack->messages); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_OPEN_DRONE_ID_MESSAGE_PACK_LEN? msg->len : MAVLINK_MSG_ID_OPEN_DRONE_ID_MESSAGE_PACK_LEN; - memset(open_drone_id_message_pack, 0, MAVLINK_MSG_ID_OPEN_DRONE_ID_MESSAGE_PACK_LEN); - memcpy(open_drone_id_message_pack, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_open_drone_id_operator_id.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_open_drone_id_operator_id.h deleted file mode 100644 index ba72d2b0..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_open_drone_id_operator_id.h +++ /dev/null @@ -1,306 +0,0 @@ -#pragma once -// MESSAGE OPEN_DRONE_ID_OPERATOR_ID PACKING - -#define MAVLINK_MSG_ID_OPEN_DRONE_ID_OPERATOR_ID 12905 - - -typedef struct __mavlink_open_drone_id_operator_id_t { - uint8_t target_system; /*< System ID (0 for broadcast).*/ - uint8_t target_component; /*< Component ID (0 for broadcast).*/ - uint8_t id_or_mac[20]; /*< Only used for drone ID data received from other UAs. See detailed description at https://mavlink.io/en/services/opendroneid.html. */ - uint8_t operator_id_type; /*< Indicates the type of the operator_id field.*/ - char operator_id[20]; /*< Text description or numeric value expressed as ASCII characters. Shall be filled with nulls in the unused portion of the field.*/ -} mavlink_open_drone_id_operator_id_t; - -#define MAVLINK_MSG_ID_OPEN_DRONE_ID_OPERATOR_ID_LEN 43 -#define MAVLINK_MSG_ID_OPEN_DRONE_ID_OPERATOR_ID_MIN_LEN 43 -#define MAVLINK_MSG_ID_12905_LEN 43 -#define MAVLINK_MSG_ID_12905_MIN_LEN 43 - -#define MAVLINK_MSG_ID_OPEN_DRONE_ID_OPERATOR_ID_CRC 49 -#define MAVLINK_MSG_ID_12905_CRC 49 - -#define MAVLINK_MSG_OPEN_DRONE_ID_OPERATOR_ID_FIELD_ID_OR_MAC_LEN 20 -#define MAVLINK_MSG_OPEN_DRONE_ID_OPERATOR_ID_FIELD_OPERATOR_ID_LEN 20 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_OPEN_DRONE_ID_OPERATOR_ID { \ - 12905, \ - "OPEN_DRONE_ID_OPERATOR_ID", \ - 5, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_open_drone_id_operator_id_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_open_drone_id_operator_id_t, target_component) }, \ - { "id_or_mac", NULL, MAVLINK_TYPE_UINT8_T, 20, 2, offsetof(mavlink_open_drone_id_operator_id_t, id_or_mac) }, \ - { "operator_id_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 22, offsetof(mavlink_open_drone_id_operator_id_t, operator_id_type) }, \ - { "operator_id", NULL, MAVLINK_TYPE_CHAR, 20, 23, offsetof(mavlink_open_drone_id_operator_id_t, operator_id) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_OPEN_DRONE_ID_OPERATOR_ID { \ - "OPEN_DRONE_ID_OPERATOR_ID", \ - 5, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_open_drone_id_operator_id_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_open_drone_id_operator_id_t, target_component) }, \ - { "id_or_mac", NULL, MAVLINK_TYPE_UINT8_T, 20, 2, offsetof(mavlink_open_drone_id_operator_id_t, id_or_mac) }, \ - { "operator_id_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 22, offsetof(mavlink_open_drone_id_operator_id_t, operator_id_type) }, \ - { "operator_id", NULL, MAVLINK_TYPE_CHAR, 20, 23, offsetof(mavlink_open_drone_id_operator_id_t, operator_id) }, \ - } \ -} -#endif - -/** - * @brief Pack a open_drone_id_operator_id message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID (0 for broadcast). - * @param target_component Component ID (0 for broadcast). - * @param id_or_mac Only used for drone ID data received from other UAs. See detailed description at https://mavlink.io/en/services/opendroneid.html. - * @param operator_id_type Indicates the type of the operator_id field. - * @param operator_id Text description or numeric value expressed as ASCII characters. Shall be filled with nulls in the unused portion of the field. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_open_drone_id_operator_id_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component, const uint8_t *id_or_mac, uint8_t operator_id_type, const char *operator_id) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_OPEN_DRONE_ID_OPERATOR_ID_LEN]; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - _mav_put_uint8_t(buf, 22, operator_id_type); - _mav_put_uint8_t_array(buf, 2, id_or_mac, 20); - _mav_put_char_array(buf, 23, operator_id, 20); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OPEN_DRONE_ID_OPERATOR_ID_LEN); -#else - mavlink_open_drone_id_operator_id_t packet; - packet.target_system = target_system; - packet.target_component = target_component; - packet.operator_id_type = operator_id_type; - mav_array_memcpy(packet.id_or_mac, id_or_mac, sizeof(uint8_t)*20); - mav_array_memcpy(packet.operator_id, operator_id, sizeof(char)*20); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_OPEN_DRONE_ID_OPERATOR_ID_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_OPEN_DRONE_ID_OPERATOR_ID; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_OPEN_DRONE_ID_OPERATOR_ID_MIN_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_OPERATOR_ID_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_OPERATOR_ID_CRC); -} - -/** - * @brief Pack a open_drone_id_operator_id message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID (0 for broadcast). - * @param target_component Component ID (0 for broadcast). - * @param id_or_mac Only used for drone ID data received from other UAs. See detailed description at https://mavlink.io/en/services/opendroneid.html. - * @param operator_id_type Indicates the type of the operator_id field. - * @param operator_id Text description or numeric value expressed as ASCII characters. Shall be filled with nulls in the unused portion of the field. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_open_drone_id_operator_id_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component,const uint8_t *id_or_mac,uint8_t operator_id_type,const char *operator_id) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_OPEN_DRONE_ID_OPERATOR_ID_LEN]; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - _mav_put_uint8_t(buf, 22, operator_id_type); - _mav_put_uint8_t_array(buf, 2, id_or_mac, 20); - _mav_put_char_array(buf, 23, operator_id, 20); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OPEN_DRONE_ID_OPERATOR_ID_LEN); -#else - mavlink_open_drone_id_operator_id_t packet; - packet.target_system = target_system; - packet.target_component = target_component; - packet.operator_id_type = operator_id_type; - mav_array_memcpy(packet.id_or_mac, id_or_mac, sizeof(uint8_t)*20); - mav_array_memcpy(packet.operator_id, operator_id, sizeof(char)*20); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_OPEN_DRONE_ID_OPERATOR_ID_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_OPEN_DRONE_ID_OPERATOR_ID; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_OPEN_DRONE_ID_OPERATOR_ID_MIN_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_OPERATOR_ID_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_OPERATOR_ID_CRC); -} - -/** - * @brief Encode a open_drone_id_operator_id struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param open_drone_id_operator_id C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_open_drone_id_operator_id_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_open_drone_id_operator_id_t* open_drone_id_operator_id) -{ - return mavlink_msg_open_drone_id_operator_id_pack(system_id, component_id, msg, open_drone_id_operator_id->target_system, open_drone_id_operator_id->target_component, open_drone_id_operator_id->id_or_mac, open_drone_id_operator_id->operator_id_type, open_drone_id_operator_id->operator_id); -} - -/** - * @brief Encode a open_drone_id_operator_id struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param open_drone_id_operator_id C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_open_drone_id_operator_id_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_open_drone_id_operator_id_t* open_drone_id_operator_id) -{ - return mavlink_msg_open_drone_id_operator_id_pack_chan(system_id, component_id, chan, msg, open_drone_id_operator_id->target_system, open_drone_id_operator_id->target_component, open_drone_id_operator_id->id_or_mac, open_drone_id_operator_id->operator_id_type, open_drone_id_operator_id->operator_id); -} - -/** - * @brief Send a open_drone_id_operator_id message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID (0 for broadcast). - * @param target_component Component ID (0 for broadcast). - * @param id_or_mac Only used for drone ID data received from other UAs. See detailed description at https://mavlink.io/en/services/opendroneid.html. - * @param operator_id_type Indicates the type of the operator_id field. - * @param operator_id Text description or numeric value expressed as ASCII characters. Shall be filled with nulls in the unused portion of the field. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_open_drone_id_operator_id_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, const uint8_t *id_or_mac, uint8_t operator_id_type, const char *operator_id) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_OPEN_DRONE_ID_OPERATOR_ID_LEN]; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - _mav_put_uint8_t(buf, 22, operator_id_type); - _mav_put_uint8_t_array(buf, 2, id_or_mac, 20); - _mav_put_char_array(buf, 23, operator_id, 20); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPEN_DRONE_ID_OPERATOR_ID, buf, MAVLINK_MSG_ID_OPEN_DRONE_ID_OPERATOR_ID_MIN_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_OPERATOR_ID_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_OPERATOR_ID_CRC); -#else - mavlink_open_drone_id_operator_id_t packet; - packet.target_system = target_system; - packet.target_component = target_component; - packet.operator_id_type = operator_id_type; - mav_array_memcpy(packet.id_or_mac, id_or_mac, sizeof(uint8_t)*20); - mav_array_memcpy(packet.operator_id, operator_id, sizeof(char)*20); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPEN_DRONE_ID_OPERATOR_ID, (const char *)&packet, MAVLINK_MSG_ID_OPEN_DRONE_ID_OPERATOR_ID_MIN_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_OPERATOR_ID_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_OPERATOR_ID_CRC); -#endif -} - -/** - * @brief Send a open_drone_id_operator_id message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_open_drone_id_operator_id_send_struct(mavlink_channel_t chan, const mavlink_open_drone_id_operator_id_t* open_drone_id_operator_id) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_open_drone_id_operator_id_send(chan, open_drone_id_operator_id->target_system, open_drone_id_operator_id->target_component, open_drone_id_operator_id->id_or_mac, open_drone_id_operator_id->operator_id_type, open_drone_id_operator_id->operator_id); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPEN_DRONE_ID_OPERATOR_ID, (const char *)open_drone_id_operator_id, MAVLINK_MSG_ID_OPEN_DRONE_ID_OPERATOR_ID_MIN_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_OPERATOR_ID_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_OPERATOR_ID_CRC); -#endif -} - -#if MAVLINK_MSG_ID_OPEN_DRONE_ID_OPERATOR_ID_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_open_drone_id_operator_id_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, const uint8_t *id_or_mac, uint8_t operator_id_type, const char *operator_id) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - _mav_put_uint8_t(buf, 22, operator_id_type); - _mav_put_uint8_t_array(buf, 2, id_or_mac, 20); - _mav_put_char_array(buf, 23, operator_id, 20); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPEN_DRONE_ID_OPERATOR_ID, buf, MAVLINK_MSG_ID_OPEN_DRONE_ID_OPERATOR_ID_MIN_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_OPERATOR_ID_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_OPERATOR_ID_CRC); -#else - mavlink_open_drone_id_operator_id_t *packet = (mavlink_open_drone_id_operator_id_t *)msgbuf; - packet->target_system = target_system; - packet->target_component = target_component; - packet->operator_id_type = operator_id_type; - mav_array_memcpy(packet->id_or_mac, id_or_mac, sizeof(uint8_t)*20); - mav_array_memcpy(packet->operator_id, operator_id, sizeof(char)*20); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPEN_DRONE_ID_OPERATOR_ID, (const char *)packet, MAVLINK_MSG_ID_OPEN_DRONE_ID_OPERATOR_ID_MIN_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_OPERATOR_ID_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_OPERATOR_ID_CRC); -#endif -} -#endif - -#endif - -// MESSAGE OPEN_DRONE_ID_OPERATOR_ID UNPACKING - - -/** - * @brief Get field target_system from open_drone_id_operator_id message - * - * @return System ID (0 for broadcast). - */ -static inline uint8_t mavlink_msg_open_drone_id_operator_id_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 0); -} - -/** - * @brief Get field target_component from open_drone_id_operator_id message - * - * @return Component ID (0 for broadcast). - */ -static inline uint8_t mavlink_msg_open_drone_id_operator_id_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 1); -} - -/** - * @brief Get field id_or_mac from open_drone_id_operator_id message - * - * @return Only used for drone ID data received from other UAs. See detailed description at https://mavlink.io/en/services/opendroneid.html. - */ -static inline uint16_t mavlink_msg_open_drone_id_operator_id_get_id_or_mac(const mavlink_message_t* msg, uint8_t *id_or_mac) -{ - return _MAV_RETURN_uint8_t_array(msg, id_or_mac, 20, 2); -} - -/** - * @brief Get field operator_id_type from open_drone_id_operator_id message - * - * @return Indicates the type of the operator_id field. - */ -static inline uint8_t mavlink_msg_open_drone_id_operator_id_get_operator_id_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 22); -} - -/** - * @brief Get field operator_id from open_drone_id_operator_id message - * - * @return Text description or numeric value expressed as ASCII characters. Shall be filled with nulls in the unused portion of the field. - */ -static inline uint16_t mavlink_msg_open_drone_id_operator_id_get_operator_id(const mavlink_message_t* msg, char *operator_id) -{ - return _MAV_RETURN_char_array(msg, operator_id, 20, 23); -} - -/** - * @brief Decode a open_drone_id_operator_id message into a struct - * - * @param msg The message to decode - * @param open_drone_id_operator_id C-struct to decode the message contents into - */ -static inline void mavlink_msg_open_drone_id_operator_id_decode(const mavlink_message_t* msg, mavlink_open_drone_id_operator_id_t* open_drone_id_operator_id) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - open_drone_id_operator_id->target_system = mavlink_msg_open_drone_id_operator_id_get_target_system(msg); - open_drone_id_operator_id->target_component = mavlink_msg_open_drone_id_operator_id_get_target_component(msg); - mavlink_msg_open_drone_id_operator_id_get_id_or_mac(msg, open_drone_id_operator_id->id_or_mac); - open_drone_id_operator_id->operator_id_type = mavlink_msg_open_drone_id_operator_id_get_operator_id_type(msg); - mavlink_msg_open_drone_id_operator_id_get_operator_id(msg, open_drone_id_operator_id->operator_id); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_OPEN_DRONE_ID_OPERATOR_ID_LEN? msg->len : MAVLINK_MSG_ID_OPEN_DRONE_ID_OPERATOR_ID_LEN; - memset(open_drone_id_operator_id, 0, MAVLINK_MSG_ID_OPEN_DRONE_ID_OPERATOR_ID_LEN); - memcpy(open_drone_id_operator_id, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_open_drone_id_self_id.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_open_drone_id_self_id.h deleted file mode 100644 index fbc787a0..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_open_drone_id_self_id.h +++ /dev/null @@ -1,306 +0,0 @@ -#pragma once -// MESSAGE OPEN_DRONE_ID_SELF_ID PACKING - -#define MAVLINK_MSG_ID_OPEN_DRONE_ID_SELF_ID 12903 - - -typedef struct __mavlink_open_drone_id_self_id_t { - uint8_t target_system; /*< System ID (0 for broadcast).*/ - uint8_t target_component; /*< Component ID (0 for broadcast).*/ - uint8_t id_or_mac[20]; /*< Only used for drone ID data received from other UAs. See detailed description at https://mavlink.io/en/services/opendroneid.html. */ - uint8_t description_type; /*< Indicates the type of the description field.*/ - char description[23]; /*< Text description or numeric value expressed as ASCII characters. Shall be filled with nulls in the unused portion of the field.*/ -} mavlink_open_drone_id_self_id_t; - -#define MAVLINK_MSG_ID_OPEN_DRONE_ID_SELF_ID_LEN 46 -#define MAVLINK_MSG_ID_OPEN_DRONE_ID_SELF_ID_MIN_LEN 46 -#define MAVLINK_MSG_ID_12903_LEN 46 -#define MAVLINK_MSG_ID_12903_MIN_LEN 46 - -#define MAVLINK_MSG_ID_OPEN_DRONE_ID_SELF_ID_CRC 249 -#define MAVLINK_MSG_ID_12903_CRC 249 - -#define MAVLINK_MSG_OPEN_DRONE_ID_SELF_ID_FIELD_ID_OR_MAC_LEN 20 -#define MAVLINK_MSG_OPEN_DRONE_ID_SELF_ID_FIELD_DESCRIPTION_LEN 23 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_OPEN_DRONE_ID_SELF_ID { \ - 12903, \ - "OPEN_DRONE_ID_SELF_ID", \ - 5, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_open_drone_id_self_id_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_open_drone_id_self_id_t, target_component) }, \ - { "id_or_mac", NULL, MAVLINK_TYPE_UINT8_T, 20, 2, offsetof(mavlink_open_drone_id_self_id_t, id_or_mac) }, \ - { "description_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 22, offsetof(mavlink_open_drone_id_self_id_t, description_type) }, \ - { "description", NULL, MAVLINK_TYPE_CHAR, 23, 23, offsetof(mavlink_open_drone_id_self_id_t, description) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_OPEN_DRONE_ID_SELF_ID { \ - "OPEN_DRONE_ID_SELF_ID", \ - 5, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_open_drone_id_self_id_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_open_drone_id_self_id_t, target_component) }, \ - { "id_or_mac", NULL, MAVLINK_TYPE_UINT8_T, 20, 2, offsetof(mavlink_open_drone_id_self_id_t, id_or_mac) }, \ - { "description_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 22, offsetof(mavlink_open_drone_id_self_id_t, description_type) }, \ - { "description", NULL, MAVLINK_TYPE_CHAR, 23, 23, offsetof(mavlink_open_drone_id_self_id_t, description) }, \ - } \ -} -#endif - -/** - * @brief Pack a open_drone_id_self_id message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID (0 for broadcast). - * @param target_component Component ID (0 for broadcast). - * @param id_or_mac Only used for drone ID data received from other UAs. See detailed description at https://mavlink.io/en/services/opendroneid.html. - * @param description_type Indicates the type of the description field. - * @param description Text description or numeric value expressed as ASCII characters. Shall be filled with nulls in the unused portion of the field. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_open_drone_id_self_id_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component, const uint8_t *id_or_mac, uint8_t description_type, const char *description) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_OPEN_DRONE_ID_SELF_ID_LEN]; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - _mav_put_uint8_t(buf, 22, description_type); - _mav_put_uint8_t_array(buf, 2, id_or_mac, 20); - _mav_put_char_array(buf, 23, description, 23); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OPEN_DRONE_ID_SELF_ID_LEN); -#else - mavlink_open_drone_id_self_id_t packet; - packet.target_system = target_system; - packet.target_component = target_component; - packet.description_type = description_type; - mav_array_memcpy(packet.id_or_mac, id_or_mac, sizeof(uint8_t)*20); - mav_array_memcpy(packet.description, description, sizeof(char)*23); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_OPEN_DRONE_ID_SELF_ID_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_OPEN_DRONE_ID_SELF_ID; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_OPEN_DRONE_ID_SELF_ID_MIN_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_SELF_ID_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_SELF_ID_CRC); -} - -/** - * @brief Pack a open_drone_id_self_id message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID (0 for broadcast). - * @param target_component Component ID (0 for broadcast). - * @param id_or_mac Only used for drone ID data received from other UAs. See detailed description at https://mavlink.io/en/services/opendroneid.html. - * @param description_type Indicates the type of the description field. - * @param description Text description or numeric value expressed as ASCII characters. Shall be filled with nulls in the unused portion of the field. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_open_drone_id_self_id_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component,const uint8_t *id_or_mac,uint8_t description_type,const char *description) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_OPEN_DRONE_ID_SELF_ID_LEN]; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - _mav_put_uint8_t(buf, 22, description_type); - _mav_put_uint8_t_array(buf, 2, id_or_mac, 20); - _mav_put_char_array(buf, 23, description, 23); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OPEN_DRONE_ID_SELF_ID_LEN); -#else - mavlink_open_drone_id_self_id_t packet; - packet.target_system = target_system; - packet.target_component = target_component; - packet.description_type = description_type; - mav_array_memcpy(packet.id_or_mac, id_or_mac, sizeof(uint8_t)*20); - mav_array_memcpy(packet.description, description, sizeof(char)*23); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_OPEN_DRONE_ID_SELF_ID_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_OPEN_DRONE_ID_SELF_ID; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_OPEN_DRONE_ID_SELF_ID_MIN_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_SELF_ID_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_SELF_ID_CRC); -} - -/** - * @brief Encode a open_drone_id_self_id struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param open_drone_id_self_id C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_open_drone_id_self_id_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_open_drone_id_self_id_t* open_drone_id_self_id) -{ - return mavlink_msg_open_drone_id_self_id_pack(system_id, component_id, msg, open_drone_id_self_id->target_system, open_drone_id_self_id->target_component, open_drone_id_self_id->id_or_mac, open_drone_id_self_id->description_type, open_drone_id_self_id->description); -} - -/** - * @brief Encode a open_drone_id_self_id struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param open_drone_id_self_id C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_open_drone_id_self_id_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_open_drone_id_self_id_t* open_drone_id_self_id) -{ - return mavlink_msg_open_drone_id_self_id_pack_chan(system_id, component_id, chan, msg, open_drone_id_self_id->target_system, open_drone_id_self_id->target_component, open_drone_id_self_id->id_or_mac, open_drone_id_self_id->description_type, open_drone_id_self_id->description); -} - -/** - * @brief Send a open_drone_id_self_id message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID (0 for broadcast). - * @param target_component Component ID (0 for broadcast). - * @param id_or_mac Only used for drone ID data received from other UAs. See detailed description at https://mavlink.io/en/services/opendroneid.html. - * @param description_type Indicates the type of the description field. - * @param description Text description or numeric value expressed as ASCII characters. Shall be filled with nulls in the unused portion of the field. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_open_drone_id_self_id_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, const uint8_t *id_or_mac, uint8_t description_type, const char *description) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_OPEN_DRONE_ID_SELF_ID_LEN]; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - _mav_put_uint8_t(buf, 22, description_type); - _mav_put_uint8_t_array(buf, 2, id_or_mac, 20); - _mav_put_char_array(buf, 23, description, 23); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPEN_DRONE_ID_SELF_ID, buf, MAVLINK_MSG_ID_OPEN_DRONE_ID_SELF_ID_MIN_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_SELF_ID_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_SELF_ID_CRC); -#else - mavlink_open_drone_id_self_id_t packet; - packet.target_system = target_system; - packet.target_component = target_component; - packet.description_type = description_type; - mav_array_memcpy(packet.id_or_mac, id_or_mac, sizeof(uint8_t)*20); - mav_array_memcpy(packet.description, description, sizeof(char)*23); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPEN_DRONE_ID_SELF_ID, (const char *)&packet, MAVLINK_MSG_ID_OPEN_DRONE_ID_SELF_ID_MIN_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_SELF_ID_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_SELF_ID_CRC); -#endif -} - -/** - * @brief Send a open_drone_id_self_id message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_open_drone_id_self_id_send_struct(mavlink_channel_t chan, const mavlink_open_drone_id_self_id_t* open_drone_id_self_id) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_open_drone_id_self_id_send(chan, open_drone_id_self_id->target_system, open_drone_id_self_id->target_component, open_drone_id_self_id->id_or_mac, open_drone_id_self_id->description_type, open_drone_id_self_id->description); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPEN_DRONE_ID_SELF_ID, (const char *)open_drone_id_self_id, MAVLINK_MSG_ID_OPEN_DRONE_ID_SELF_ID_MIN_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_SELF_ID_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_SELF_ID_CRC); -#endif -} - -#if MAVLINK_MSG_ID_OPEN_DRONE_ID_SELF_ID_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_open_drone_id_self_id_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, const uint8_t *id_or_mac, uint8_t description_type, const char *description) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - _mav_put_uint8_t(buf, 22, description_type); - _mav_put_uint8_t_array(buf, 2, id_or_mac, 20); - _mav_put_char_array(buf, 23, description, 23); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPEN_DRONE_ID_SELF_ID, buf, MAVLINK_MSG_ID_OPEN_DRONE_ID_SELF_ID_MIN_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_SELF_ID_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_SELF_ID_CRC); -#else - mavlink_open_drone_id_self_id_t *packet = (mavlink_open_drone_id_self_id_t *)msgbuf; - packet->target_system = target_system; - packet->target_component = target_component; - packet->description_type = description_type; - mav_array_memcpy(packet->id_or_mac, id_or_mac, sizeof(uint8_t)*20); - mav_array_memcpy(packet->description, description, sizeof(char)*23); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPEN_DRONE_ID_SELF_ID, (const char *)packet, MAVLINK_MSG_ID_OPEN_DRONE_ID_SELF_ID_MIN_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_SELF_ID_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_SELF_ID_CRC); -#endif -} -#endif - -#endif - -// MESSAGE OPEN_DRONE_ID_SELF_ID UNPACKING - - -/** - * @brief Get field target_system from open_drone_id_self_id message - * - * @return System ID (0 for broadcast). - */ -static inline uint8_t mavlink_msg_open_drone_id_self_id_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 0); -} - -/** - * @brief Get field target_component from open_drone_id_self_id message - * - * @return Component ID (0 for broadcast). - */ -static inline uint8_t mavlink_msg_open_drone_id_self_id_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 1); -} - -/** - * @brief Get field id_or_mac from open_drone_id_self_id message - * - * @return Only used for drone ID data received from other UAs. See detailed description at https://mavlink.io/en/services/opendroneid.html. - */ -static inline uint16_t mavlink_msg_open_drone_id_self_id_get_id_or_mac(const mavlink_message_t* msg, uint8_t *id_or_mac) -{ - return _MAV_RETURN_uint8_t_array(msg, id_or_mac, 20, 2); -} - -/** - * @brief Get field description_type from open_drone_id_self_id message - * - * @return Indicates the type of the description field. - */ -static inline uint8_t mavlink_msg_open_drone_id_self_id_get_description_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 22); -} - -/** - * @brief Get field description from open_drone_id_self_id message - * - * @return Text description or numeric value expressed as ASCII characters. Shall be filled with nulls in the unused portion of the field. - */ -static inline uint16_t mavlink_msg_open_drone_id_self_id_get_description(const mavlink_message_t* msg, char *description) -{ - return _MAV_RETURN_char_array(msg, description, 23, 23); -} - -/** - * @brief Decode a open_drone_id_self_id message into a struct - * - * @param msg The message to decode - * @param open_drone_id_self_id C-struct to decode the message contents into - */ -static inline void mavlink_msg_open_drone_id_self_id_decode(const mavlink_message_t* msg, mavlink_open_drone_id_self_id_t* open_drone_id_self_id) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - open_drone_id_self_id->target_system = mavlink_msg_open_drone_id_self_id_get_target_system(msg); - open_drone_id_self_id->target_component = mavlink_msg_open_drone_id_self_id_get_target_component(msg); - mavlink_msg_open_drone_id_self_id_get_id_or_mac(msg, open_drone_id_self_id->id_or_mac); - open_drone_id_self_id->description_type = mavlink_msg_open_drone_id_self_id_get_description_type(msg); - mavlink_msg_open_drone_id_self_id_get_description(msg, open_drone_id_self_id->description); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_OPEN_DRONE_ID_SELF_ID_LEN? msg->len : MAVLINK_MSG_ID_OPEN_DRONE_ID_SELF_ID_LEN; - memset(open_drone_id_self_id, 0, MAVLINK_MSG_ID_OPEN_DRONE_ID_SELF_ID_LEN); - memcpy(open_drone_id_self_id, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_open_drone_id_system.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_open_drone_id_system.h deleted file mode 100644 index 876c0595..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_open_drone_id_system.h +++ /dev/null @@ -1,555 +0,0 @@ -#pragma once -// MESSAGE OPEN_DRONE_ID_SYSTEM PACKING - -#define MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM 12904 - - -typedef struct __mavlink_open_drone_id_system_t { - int32_t operator_latitude; /*< [degE7] Latitude of the operator. If unknown: 0 (both Lat/Lon).*/ - int32_t operator_longitude; /*< [degE7] Longitude of the operator. If unknown: 0 (both Lat/Lon).*/ - float area_ceiling; /*< [m] Area Operations Ceiling relative to WGS84. If unknown: -1000 m. Used only for swarms/multiple UA.*/ - float area_floor; /*< [m] Area Operations Floor relative to WGS84. If unknown: -1000 m. Used only for swarms/multiple UA.*/ - float operator_altitude_geo; /*< [m] Geodetic altitude of the operator relative to WGS84. If unknown: -1000 m.*/ - uint32_t timestamp; /*< [s] 32 bit Unix Timestamp in seconds since 00:00:00 01/01/2019.*/ - uint16_t area_count; /*< Number of aircraft in the area, group or formation (default 1). Used only for swarms/multiple UA.*/ - uint16_t area_radius; /*< [m] Radius of the cylindrical area of the group or formation (default 0). Used only for swarms/multiple UA.*/ - uint8_t target_system; /*< System ID (0 for broadcast).*/ - uint8_t target_component; /*< Component ID (0 for broadcast).*/ - uint8_t id_or_mac[20]; /*< Only used for drone ID data received from other UAs. See detailed description at https://mavlink.io/en/services/opendroneid.html. */ - uint8_t operator_location_type; /*< Specifies the operator location type.*/ - uint8_t classification_type; /*< Specifies the classification type of the UA.*/ - uint8_t category_eu; /*< When classification_type is MAV_ODID_CLASSIFICATION_TYPE_EU, specifies the category of the UA.*/ - uint8_t class_eu; /*< When classification_type is MAV_ODID_CLASSIFICATION_TYPE_EU, specifies the class of the UA.*/ -} mavlink_open_drone_id_system_t; - -#define MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_LEN 54 -#define MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_MIN_LEN 54 -#define MAVLINK_MSG_ID_12904_LEN 54 -#define MAVLINK_MSG_ID_12904_MIN_LEN 54 - -#define MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_CRC 77 -#define MAVLINK_MSG_ID_12904_CRC 77 - -#define MAVLINK_MSG_OPEN_DRONE_ID_SYSTEM_FIELD_ID_OR_MAC_LEN 20 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_OPEN_DRONE_ID_SYSTEM { \ - 12904, \ - "OPEN_DRONE_ID_SYSTEM", \ - 15, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 28, offsetof(mavlink_open_drone_id_system_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 29, offsetof(mavlink_open_drone_id_system_t, target_component) }, \ - { "id_or_mac", NULL, MAVLINK_TYPE_UINT8_T, 20, 30, offsetof(mavlink_open_drone_id_system_t, id_or_mac) }, \ - { "operator_location_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 50, offsetof(mavlink_open_drone_id_system_t, operator_location_type) }, \ - { "classification_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 51, offsetof(mavlink_open_drone_id_system_t, classification_type) }, \ - { "operator_latitude", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_open_drone_id_system_t, operator_latitude) }, \ - { "operator_longitude", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_open_drone_id_system_t, operator_longitude) }, \ - { "area_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_open_drone_id_system_t, area_count) }, \ - { "area_radius", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_open_drone_id_system_t, area_radius) }, \ - { "area_ceiling", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_open_drone_id_system_t, area_ceiling) }, \ - { "area_floor", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_open_drone_id_system_t, area_floor) }, \ - { "category_eu", NULL, MAVLINK_TYPE_UINT8_T, 0, 52, offsetof(mavlink_open_drone_id_system_t, category_eu) }, \ - { "class_eu", NULL, MAVLINK_TYPE_UINT8_T, 0, 53, offsetof(mavlink_open_drone_id_system_t, class_eu) }, \ - { "operator_altitude_geo", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_open_drone_id_system_t, operator_altitude_geo) }, \ - { "timestamp", NULL, MAVLINK_TYPE_UINT32_T, 0, 20, offsetof(mavlink_open_drone_id_system_t, timestamp) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_OPEN_DRONE_ID_SYSTEM { \ - "OPEN_DRONE_ID_SYSTEM", \ - 15, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 28, offsetof(mavlink_open_drone_id_system_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 29, offsetof(mavlink_open_drone_id_system_t, target_component) }, \ - { "id_or_mac", NULL, MAVLINK_TYPE_UINT8_T, 20, 30, offsetof(mavlink_open_drone_id_system_t, id_or_mac) }, \ - { "operator_location_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 50, offsetof(mavlink_open_drone_id_system_t, operator_location_type) }, \ - { "classification_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 51, offsetof(mavlink_open_drone_id_system_t, classification_type) }, \ - { "operator_latitude", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_open_drone_id_system_t, operator_latitude) }, \ - { "operator_longitude", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_open_drone_id_system_t, operator_longitude) }, \ - { "area_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_open_drone_id_system_t, area_count) }, \ - { "area_radius", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_open_drone_id_system_t, area_radius) }, \ - { "area_ceiling", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_open_drone_id_system_t, area_ceiling) }, \ - { "area_floor", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_open_drone_id_system_t, area_floor) }, \ - { "category_eu", NULL, MAVLINK_TYPE_UINT8_T, 0, 52, offsetof(mavlink_open_drone_id_system_t, category_eu) }, \ - { "class_eu", NULL, MAVLINK_TYPE_UINT8_T, 0, 53, offsetof(mavlink_open_drone_id_system_t, class_eu) }, \ - { "operator_altitude_geo", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_open_drone_id_system_t, operator_altitude_geo) }, \ - { "timestamp", NULL, MAVLINK_TYPE_UINT32_T, 0, 20, offsetof(mavlink_open_drone_id_system_t, timestamp) }, \ - } \ -} -#endif - -/** - * @brief Pack a open_drone_id_system message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID (0 for broadcast). - * @param target_component Component ID (0 for broadcast). - * @param id_or_mac Only used for drone ID data received from other UAs. See detailed description at https://mavlink.io/en/services/opendroneid.html. - * @param operator_location_type Specifies the operator location type. - * @param classification_type Specifies the classification type of the UA. - * @param operator_latitude [degE7] Latitude of the operator. If unknown: 0 (both Lat/Lon). - * @param operator_longitude [degE7] Longitude of the operator. If unknown: 0 (both Lat/Lon). - * @param area_count Number of aircraft in the area, group or formation (default 1). Used only for swarms/multiple UA. - * @param area_radius [m] Radius of the cylindrical area of the group or formation (default 0). Used only for swarms/multiple UA. - * @param area_ceiling [m] Area Operations Ceiling relative to WGS84. If unknown: -1000 m. Used only for swarms/multiple UA. - * @param area_floor [m] Area Operations Floor relative to WGS84. If unknown: -1000 m. Used only for swarms/multiple UA. - * @param category_eu When classification_type is MAV_ODID_CLASSIFICATION_TYPE_EU, specifies the category of the UA. - * @param class_eu When classification_type is MAV_ODID_CLASSIFICATION_TYPE_EU, specifies the class of the UA. - * @param operator_altitude_geo [m] Geodetic altitude of the operator relative to WGS84. If unknown: -1000 m. - * @param timestamp [s] 32 bit Unix Timestamp in seconds since 00:00:00 01/01/2019. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_open_drone_id_system_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component, const uint8_t *id_or_mac, uint8_t operator_location_type, uint8_t classification_type, int32_t operator_latitude, int32_t operator_longitude, uint16_t area_count, uint16_t area_radius, float area_ceiling, float area_floor, uint8_t category_eu, uint8_t class_eu, float operator_altitude_geo, uint32_t timestamp) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_LEN]; - _mav_put_int32_t(buf, 0, operator_latitude); - _mav_put_int32_t(buf, 4, operator_longitude); - _mav_put_float(buf, 8, area_ceiling); - _mav_put_float(buf, 12, area_floor); - _mav_put_float(buf, 16, operator_altitude_geo); - _mav_put_uint32_t(buf, 20, timestamp); - _mav_put_uint16_t(buf, 24, area_count); - _mav_put_uint16_t(buf, 26, area_radius); - _mav_put_uint8_t(buf, 28, target_system); - _mav_put_uint8_t(buf, 29, target_component); - _mav_put_uint8_t(buf, 50, operator_location_type); - _mav_put_uint8_t(buf, 51, classification_type); - _mav_put_uint8_t(buf, 52, category_eu); - _mav_put_uint8_t(buf, 53, class_eu); - _mav_put_uint8_t_array(buf, 30, id_or_mac, 20); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_LEN); -#else - mavlink_open_drone_id_system_t packet; - packet.operator_latitude = operator_latitude; - packet.operator_longitude = operator_longitude; - packet.area_ceiling = area_ceiling; - packet.area_floor = area_floor; - packet.operator_altitude_geo = operator_altitude_geo; - packet.timestamp = timestamp; - packet.area_count = area_count; - packet.area_radius = area_radius; - packet.target_system = target_system; - packet.target_component = target_component; - packet.operator_location_type = operator_location_type; - packet.classification_type = classification_type; - packet.category_eu = category_eu; - packet.class_eu = class_eu; - mav_array_memcpy(packet.id_or_mac, id_or_mac, sizeof(uint8_t)*20); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_MIN_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_CRC); -} - -/** - * @brief Pack a open_drone_id_system message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID (0 for broadcast). - * @param target_component Component ID (0 for broadcast). - * @param id_or_mac Only used for drone ID data received from other UAs. See detailed description at https://mavlink.io/en/services/opendroneid.html. - * @param operator_location_type Specifies the operator location type. - * @param classification_type Specifies the classification type of the UA. - * @param operator_latitude [degE7] Latitude of the operator. If unknown: 0 (both Lat/Lon). - * @param operator_longitude [degE7] Longitude of the operator. If unknown: 0 (both Lat/Lon). - * @param area_count Number of aircraft in the area, group or formation (default 1). Used only for swarms/multiple UA. - * @param area_radius [m] Radius of the cylindrical area of the group or formation (default 0). Used only for swarms/multiple UA. - * @param area_ceiling [m] Area Operations Ceiling relative to WGS84. If unknown: -1000 m. Used only for swarms/multiple UA. - * @param area_floor [m] Area Operations Floor relative to WGS84. If unknown: -1000 m. Used only for swarms/multiple UA. - * @param category_eu When classification_type is MAV_ODID_CLASSIFICATION_TYPE_EU, specifies the category of the UA. - * @param class_eu When classification_type is MAV_ODID_CLASSIFICATION_TYPE_EU, specifies the class of the UA. - * @param operator_altitude_geo [m] Geodetic altitude of the operator relative to WGS84. If unknown: -1000 m. - * @param timestamp [s] 32 bit Unix Timestamp in seconds since 00:00:00 01/01/2019. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_open_drone_id_system_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component,const uint8_t *id_or_mac,uint8_t operator_location_type,uint8_t classification_type,int32_t operator_latitude,int32_t operator_longitude,uint16_t area_count,uint16_t area_radius,float area_ceiling,float area_floor,uint8_t category_eu,uint8_t class_eu,float operator_altitude_geo,uint32_t timestamp) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_LEN]; - _mav_put_int32_t(buf, 0, operator_latitude); - _mav_put_int32_t(buf, 4, operator_longitude); - _mav_put_float(buf, 8, area_ceiling); - _mav_put_float(buf, 12, area_floor); - _mav_put_float(buf, 16, operator_altitude_geo); - _mav_put_uint32_t(buf, 20, timestamp); - _mav_put_uint16_t(buf, 24, area_count); - _mav_put_uint16_t(buf, 26, area_radius); - _mav_put_uint8_t(buf, 28, target_system); - _mav_put_uint8_t(buf, 29, target_component); - _mav_put_uint8_t(buf, 50, operator_location_type); - _mav_put_uint8_t(buf, 51, classification_type); - _mav_put_uint8_t(buf, 52, category_eu); - _mav_put_uint8_t(buf, 53, class_eu); - _mav_put_uint8_t_array(buf, 30, id_or_mac, 20); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_LEN); -#else - mavlink_open_drone_id_system_t packet; - packet.operator_latitude = operator_latitude; - packet.operator_longitude = operator_longitude; - packet.area_ceiling = area_ceiling; - packet.area_floor = area_floor; - packet.operator_altitude_geo = operator_altitude_geo; - packet.timestamp = timestamp; - packet.area_count = area_count; - packet.area_radius = area_radius; - packet.target_system = target_system; - packet.target_component = target_component; - packet.operator_location_type = operator_location_type; - packet.classification_type = classification_type; - packet.category_eu = category_eu; - packet.class_eu = class_eu; - mav_array_memcpy(packet.id_or_mac, id_or_mac, sizeof(uint8_t)*20); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_MIN_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_CRC); -} - -/** - * @brief Encode a open_drone_id_system struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param open_drone_id_system C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_open_drone_id_system_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_open_drone_id_system_t* open_drone_id_system) -{ - return mavlink_msg_open_drone_id_system_pack(system_id, component_id, msg, open_drone_id_system->target_system, open_drone_id_system->target_component, open_drone_id_system->id_or_mac, open_drone_id_system->operator_location_type, open_drone_id_system->classification_type, open_drone_id_system->operator_latitude, open_drone_id_system->operator_longitude, open_drone_id_system->area_count, open_drone_id_system->area_radius, open_drone_id_system->area_ceiling, open_drone_id_system->area_floor, open_drone_id_system->category_eu, open_drone_id_system->class_eu, open_drone_id_system->operator_altitude_geo, open_drone_id_system->timestamp); -} - -/** - * @brief Encode a open_drone_id_system struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param open_drone_id_system C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_open_drone_id_system_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_open_drone_id_system_t* open_drone_id_system) -{ - return mavlink_msg_open_drone_id_system_pack_chan(system_id, component_id, chan, msg, open_drone_id_system->target_system, open_drone_id_system->target_component, open_drone_id_system->id_or_mac, open_drone_id_system->operator_location_type, open_drone_id_system->classification_type, open_drone_id_system->operator_latitude, open_drone_id_system->operator_longitude, open_drone_id_system->area_count, open_drone_id_system->area_radius, open_drone_id_system->area_ceiling, open_drone_id_system->area_floor, open_drone_id_system->category_eu, open_drone_id_system->class_eu, open_drone_id_system->operator_altitude_geo, open_drone_id_system->timestamp); -} - -/** - * @brief Send a open_drone_id_system message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID (0 for broadcast). - * @param target_component Component ID (0 for broadcast). - * @param id_or_mac Only used for drone ID data received from other UAs. See detailed description at https://mavlink.io/en/services/opendroneid.html. - * @param operator_location_type Specifies the operator location type. - * @param classification_type Specifies the classification type of the UA. - * @param operator_latitude [degE7] Latitude of the operator. If unknown: 0 (both Lat/Lon). - * @param operator_longitude [degE7] Longitude of the operator. If unknown: 0 (both Lat/Lon). - * @param area_count Number of aircraft in the area, group or formation (default 1). Used only for swarms/multiple UA. - * @param area_radius [m] Radius of the cylindrical area of the group or formation (default 0). Used only for swarms/multiple UA. - * @param area_ceiling [m] Area Operations Ceiling relative to WGS84. If unknown: -1000 m. Used only for swarms/multiple UA. - * @param area_floor [m] Area Operations Floor relative to WGS84. If unknown: -1000 m. Used only for swarms/multiple UA. - * @param category_eu When classification_type is MAV_ODID_CLASSIFICATION_TYPE_EU, specifies the category of the UA. - * @param class_eu When classification_type is MAV_ODID_CLASSIFICATION_TYPE_EU, specifies the class of the UA. - * @param operator_altitude_geo [m] Geodetic altitude of the operator relative to WGS84. If unknown: -1000 m. - * @param timestamp [s] 32 bit Unix Timestamp in seconds since 00:00:00 01/01/2019. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_open_drone_id_system_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, const uint8_t *id_or_mac, uint8_t operator_location_type, uint8_t classification_type, int32_t operator_latitude, int32_t operator_longitude, uint16_t area_count, uint16_t area_radius, float area_ceiling, float area_floor, uint8_t category_eu, uint8_t class_eu, float operator_altitude_geo, uint32_t timestamp) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_LEN]; - _mav_put_int32_t(buf, 0, operator_latitude); - _mav_put_int32_t(buf, 4, operator_longitude); - _mav_put_float(buf, 8, area_ceiling); - _mav_put_float(buf, 12, area_floor); - _mav_put_float(buf, 16, operator_altitude_geo); - _mav_put_uint32_t(buf, 20, timestamp); - _mav_put_uint16_t(buf, 24, area_count); - _mav_put_uint16_t(buf, 26, area_radius); - _mav_put_uint8_t(buf, 28, target_system); - _mav_put_uint8_t(buf, 29, target_component); - _mav_put_uint8_t(buf, 50, operator_location_type); - _mav_put_uint8_t(buf, 51, classification_type); - _mav_put_uint8_t(buf, 52, category_eu); - _mav_put_uint8_t(buf, 53, class_eu); - _mav_put_uint8_t_array(buf, 30, id_or_mac, 20); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM, buf, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_MIN_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_CRC); -#else - mavlink_open_drone_id_system_t packet; - packet.operator_latitude = operator_latitude; - packet.operator_longitude = operator_longitude; - packet.area_ceiling = area_ceiling; - packet.area_floor = area_floor; - packet.operator_altitude_geo = operator_altitude_geo; - packet.timestamp = timestamp; - packet.area_count = area_count; - packet.area_radius = area_radius; - packet.target_system = target_system; - packet.target_component = target_component; - packet.operator_location_type = operator_location_type; - packet.classification_type = classification_type; - packet.category_eu = category_eu; - packet.class_eu = class_eu; - mav_array_memcpy(packet.id_or_mac, id_or_mac, sizeof(uint8_t)*20); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM, (const char *)&packet, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_MIN_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_CRC); -#endif -} - -/** - * @brief Send a open_drone_id_system message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_open_drone_id_system_send_struct(mavlink_channel_t chan, const mavlink_open_drone_id_system_t* open_drone_id_system) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_open_drone_id_system_send(chan, open_drone_id_system->target_system, open_drone_id_system->target_component, open_drone_id_system->id_or_mac, open_drone_id_system->operator_location_type, open_drone_id_system->classification_type, open_drone_id_system->operator_latitude, open_drone_id_system->operator_longitude, open_drone_id_system->area_count, open_drone_id_system->area_radius, open_drone_id_system->area_ceiling, open_drone_id_system->area_floor, open_drone_id_system->category_eu, open_drone_id_system->class_eu, open_drone_id_system->operator_altitude_geo, open_drone_id_system->timestamp); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM, (const char *)open_drone_id_system, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_MIN_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_CRC); -#endif -} - -#if MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_open_drone_id_system_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, const uint8_t *id_or_mac, uint8_t operator_location_type, uint8_t classification_type, int32_t operator_latitude, int32_t operator_longitude, uint16_t area_count, uint16_t area_radius, float area_ceiling, float area_floor, uint8_t category_eu, uint8_t class_eu, float operator_altitude_geo, uint32_t timestamp) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_int32_t(buf, 0, operator_latitude); - _mav_put_int32_t(buf, 4, operator_longitude); - _mav_put_float(buf, 8, area_ceiling); - _mav_put_float(buf, 12, area_floor); - _mav_put_float(buf, 16, operator_altitude_geo); - _mav_put_uint32_t(buf, 20, timestamp); - _mav_put_uint16_t(buf, 24, area_count); - _mav_put_uint16_t(buf, 26, area_radius); - _mav_put_uint8_t(buf, 28, target_system); - _mav_put_uint8_t(buf, 29, target_component); - _mav_put_uint8_t(buf, 50, operator_location_type); - _mav_put_uint8_t(buf, 51, classification_type); - _mav_put_uint8_t(buf, 52, category_eu); - _mav_put_uint8_t(buf, 53, class_eu); - _mav_put_uint8_t_array(buf, 30, id_or_mac, 20); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM, buf, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_MIN_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_CRC); -#else - mavlink_open_drone_id_system_t *packet = (mavlink_open_drone_id_system_t *)msgbuf; - packet->operator_latitude = operator_latitude; - packet->operator_longitude = operator_longitude; - packet->area_ceiling = area_ceiling; - packet->area_floor = area_floor; - packet->operator_altitude_geo = operator_altitude_geo; - packet->timestamp = timestamp; - packet->area_count = area_count; - packet->area_radius = area_radius; - packet->target_system = target_system; - packet->target_component = target_component; - packet->operator_location_type = operator_location_type; - packet->classification_type = classification_type; - packet->category_eu = category_eu; - packet->class_eu = class_eu; - mav_array_memcpy(packet->id_or_mac, id_or_mac, sizeof(uint8_t)*20); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM, (const char *)packet, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_MIN_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_CRC); -#endif -} -#endif - -#endif - -// MESSAGE OPEN_DRONE_ID_SYSTEM UNPACKING - - -/** - * @brief Get field target_system from open_drone_id_system message - * - * @return System ID (0 for broadcast). - */ -static inline uint8_t mavlink_msg_open_drone_id_system_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 28); -} - -/** - * @brief Get field target_component from open_drone_id_system message - * - * @return Component ID (0 for broadcast). - */ -static inline uint8_t mavlink_msg_open_drone_id_system_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 29); -} - -/** - * @brief Get field id_or_mac from open_drone_id_system message - * - * @return Only used for drone ID data received from other UAs. See detailed description at https://mavlink.io/en/services/opendroneid.html. - */ -static inline uint16_t mavlink_msg_open_drone_id_system_get_id_or_mac(const mavlink_message_t* msg, uint8_t *id_or_mac) -{ - return _MAV_RETURN_uint8_t_array(msg, id_or_mac, 20, 30); -} - -/** - * @brief Get field operator_location_type from open_drone_id_system message - * - * @return Specifies the operator location type. - */ -static inline uint8_t mavlink_msg_open_drone_id_system_get_operator_location_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 50); -} - -/** - * @brief Get field classification_type from open_drone_id_system message - * - * @return Specifies the classification type of the UA. - */ -static inline uint8_t mavlink_msg_open_drone_id_system_get_classification_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 51); -} - -/** - * @brief Get field operator_latitude from open_drone_id_system message - * - * @return [degE7] Latitude of the operator. If unknown: 0 (both Lat/Lon). - */ -static inline int32_t mavlink_msg_open_drone_id_system_get_operator_latitude(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 0); -} - -/** - * @brief Get field operator_longitude from open_drone_id_system message - * - * @return [degE7] Longitude of the operator. If unknown: 0 (both Lat/Lon). - */ -static inline int32_t mavlink_msg_open_drone_id_system_get_operator_longitude(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 4); -} - -/** - * @brief Get field area_count from open_drone_id_system message - * - * @return Number of aircraft in the area, group or formation (default 1). Used only for swarms/multiple UA. - */ -static inline uint16_t mavlink_msg_open_drone_id_system_get_area_count(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 24); -} - -/** - * @brief Get field area_radius from open_drone_id_system message - * - * @return [m] Radius of the cylindrical area of the group or formation (default 0). Used only for swarms/multiple UA. - */ -static inline uint16_t mavlink_msg_open_drone_id_system_get_area_radius(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 26); -} - -/** - * @brief Get field area_ceiling from open_drone_id_system message - * - * @return [m] Area Operations Ceiling relative to WGS84. If unknown: -1000 m. Used only for swarms/multiple UA. - */ -static inline float mavlink_msg_open_drone_id_system_get_area_ceiling(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field area_floor from open_drone_id_system message - * - * @return [m] Area Operations Floor relative to WGS84. If unknown: -1000 m. Used only for swarms/multiple UA. - */ -static inline float mavlink_msg_open_drone_id_system_get_area_floor(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field category_eu from open_drone_id_system message - * - * @return When classification_type is MAV_ODID_CLASSIFICATION_TYPE_EU, specifies the category of the UA. - */ -static inline uint8_t mavlink_msg_open_drone_id_system_get_category_eu(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 52); -} - -/** - * @brief Get field class_eu from open_drone_id_system message - * - * @return When classification_type is MAV_ODID_CLASSIFICATION_TYPE_EU, specifies the class of the UA. - */ -static inline uint8_t mavlink_msg_open_drone_id_system_get_class_eu(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 53); -} - -/** - * @brief Get field operator_altitude_geo from open_drone_id_system message - * - * @return [m] Geodetic altitude of the operator relative to WGS84. If unknown: -1000 m. - */ -static inline float mavlink_msg_open_drone_id_system_get_operator_altitude_geo(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field timestamp from open_drone_id_system message - * - * @return [s] 32 bit Unix Timestamp in seconds since 00:00:00 01/01/2019. - */ -static inline uint32_t mavlink_msg_open_drone_id_system_get_timestamp(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 20); -} - -/** - * @brief Decode a open_drone_id_system message into a struct - * - * @param msg The message to decode - * @param open_drone_id_system C-struct to decode the message contents into - */ -static inline void mavlink_msg_open_drone_id_system_decode(const mavlink_message_t* msg, mavlink_open_drone_id_system_t* open_drone_id_system) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - open_drone_id_system->operator_latitude = mavlink_msg_open_drone_id_system_get_operator_latitude(msg); - open_drone_id_system->operator_longitude = mavlink_msg_open_drone_id_system_get_operator_longitude(msg); - open_drone_id_system->area_ceiling = mavlink_msg_open_drone_id_system_get_area_ceiling(msg); - open_drone_id_system->area_floor = mavlink_msg_open_drone_id_system_get_area_floor(msg); - open_drone_id_system->operator_altitude_geo = mavlink_msg_open_drone_id_system_get_operator_altitude_geo(msg); - open_drone_id_system->timestamp = mavlink_msg_open_drone_id_system_get_timestamp(msg); - open_drone_id_system->area_count = mavlink_msg_open_drone_id_system_get_area_count(msg); - open_drone_id_system->area_radius = mavlink_msg_open_drone_id_system_get_area_radius(msg); - open_drone_id_system->target_system = mavlink_msg_open_drone_id_system_get_target_system(msg); - open_drone_id_system->target_component = mavlink_msg_open_drone_id_system_get_target_component(msg); - mavlink_msg_open_drone_id_system_get_id_or_mac(msg, open_drone_id_system->id_or_mac); - open_drone_id_system->operator_location_type = mavlink_msg_open_drone_id_system_get_operator_location_type(msg); - open_drone_id_system->classification_type = mavlink_msg_open_drone_id_system_get_classification_type(msg); - open_drone_id_system->category_eu = mavlink_msg_open_drone_id_system_get_category_eu(msg); - open_drone_id_system->class_eu = mavlink_msg_open_drone_id_system_get_class_eu(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_LEN? msg->len : MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_LEN; - memset(open_drone_id_system, 0, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_LEN); - memcpy(open_drone_id_system, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_open_drone_id_system_update.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_open_drone_id_system_update.h deleted file mode 100644 index 8549cc90..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_open_drone_id_system_update.h +++ /dev/null @@ -1,338 +0,0 @@ -#pragma once -// MESSAGE OPEN_DRONE_ID_SYSTEM_UPDATE PACKING - -#define MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_UPDATE 12919 - - -typedef struct __mavlink_open_drone_id_system_update_t { - int32_t operator_latitude; /*< [degE7] Latitude of the operator. If unknown: 0 (both Lat/Lon).*/ - int32_t operator_longitude; /*< [degE7] Longitude of the operator. If unknown: 0 (both Lat/Lon).*/ - float operator_altitude_geo; /*< [m] Geodetic altitude of the operator relative to WGS84. If unknown: -1000 m.*/ - uint32_t timestamp; /*< [s] 32 bit Unix Timestamp in seconds since 00:00:00 01/01/2019.*/ - uint8_t target_system; /*< System ID (0 for broadcast).*/ - uint8_t target_component; /*< Component ID (0 for broadcast).*/ -} mavlink_open_drone_id_system_update_t; - -#define MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_UPDATE_LEN 18 -#define MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_UPDATE_MIN_LEN 18 -#define MAVLINK_MSG_ID_12919_LEN 18 -#define MAVLINK_MSG_ID_12919_MIN_LEN 18 - -#define MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_UPDATE_CRC 7 -#define MAVLINK_MSG_ID_12919_CRC 7 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_OPEN_DRONE_ID_SYSTEM_UPDATE { \ - 12919, \ - "OPEN_DRONE_ID_SYSTEM_UPDATE", \ - 6, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_open_drone_id_system_update_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 17, offsetof(mavlink_open_drone_id_system_update_t, target_component) }, \ - { "operator_latitude", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_open_drone_id_system_update_t, operator_latitude) }, \ - { "operator_longitude", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_open_drone_id_system_update_t, operator_longitude) }, \ - { "operator_altitude_geo", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_open_drone_id_system_update_t, operator_altitude_geo) }, \ - { "timestamp", NULL, MAVLINK_TYPE_UINT32_T, 0, 12, offsetof(mavlink_open_drone_id_system_update_t, timestamp) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_OPEN_DRONE_ID_SYSTEM_UPDATE { \ - "OPEN_DRONE_ID_SYSTEM_UPDATE", \ - 6, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_open_drone_id_system_update_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 17, offsetof(mavlink_open_drone_id_system_update_t, target_component) }, \ - { "operator_latitude", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_open_drone_id_system_update_t, operator_latitude) }, \ - { "operator_longitude", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_open_drone_id_system_update_t, operator_longitude) }, \ - { "operator_altitude_geo", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_open_drone_id_system_update_t, operator_altitude_geo) }, \ - { "timestamp", NULL, MAVLINK_TYPE_UINT32_T, 0, 12, offsetof(mavlink_open_drone_id_system_update_t, timestamp) }, \ - } \ -} -#endif - -/** - * @brief Pack a open_drone_id_system_update message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID (0 for broadcast). - * @param target_component Component ID (0 for broadcast). - * @param operator_latitude [degE7] Latitude of the operator. If unknown: 0 (both Lat/Lon). - * @param operator_longitude [degE7] Longitude of the operator. If unknown: 0 (both Lat/Lon). - * @param operator_altitude_geo [m] Geodetic altitude of the operator relative to WGS84. If unknown: -1000 m. - * @param timestamp [s] 32 bit Unix Timestamp in seconds since 00:00:00 01/01/2019. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_open_drone_id_system_update_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component, int32_t operator_latitude, int32_t operator_longitude, float operator_altitude_geo, uint32_t timestamp) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_UPDATE_LEN]; - _mav_put_int32_t(buf, 0, operator_latitude); - _mav_put_int32_t(buf, 4, operator_longitude); - _mav_put_float(buf, 8, operator_altitude_geo); - _mav_put_uint32_t(buf, 12, timestamp); - _mav_put_uint8_t(buf, 16, target_system); - _mav_put_uint8_t(buf, 17, target_component); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_UPDATE_LEN); -#else - mavlink_open_drone_id_system_update_t packet; - packet.operator_latitude = operator_latitude; - packet.operator_longitude = operator_longitude; - packet.operator_altitude_geo = operator_altitude_geo; - packet.timestamp = timestamp; - packet.target_system = target_system; - packet.target_component = target_component; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_UPDATE_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_UPDATE; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_UPDATE_MIN_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_UPDATE_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_UPDATE_CRC); -} - -/** - * @brief Pack a open_drone_id_system_update message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID (0 for broadcast). - * @param target_component Component ID (0 for broadcast). - * @param operator_latitude [degE7] Latitude of the operator. If unknown: 0 (both Lat/Lon). - * @param operator_longitude [degE7] Longitude of the operator. If unknown: 0 (both Lat/Lon). - * @param operator_altitude_geo [m] Geodetic altitude of the operator relative to WGS84. If unknown: -1000 m. - * @param timestamp [s] 32 bit Unix Timestamp in seconds since 00:00:00 01/01/2019. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_open_drone_id_system_update_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component,int32_t operator_latitude,int32_t operator_longitude,float operator_altitude_geo,uint32_t timestamp) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_UPDATE_LEN]; - _mav_put_int32_t(buf, 0, operator_latitude); - _mav_put_int32_t(buf, 4, operator_longitude); - _mav_put_float(buf, 8, operator_altitude_geo); - _mav_put_uint32_t(buf, 12, timestamp); - _mav_put_uint8_t(buf, 16, target_system); - _mav_put_uint8_t(buf, 17, target_component); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_UPDATE_LEN); -#else - mavlink_open_drone_id_system_update_t packet; - packet.operator_latitude = operator_latitude; - packet.operator_longitude = operator_longitude; - packet.operator_altitude_geo = operator_altitude_geo; - packet.timestamp = timestamp; - packet.target_system = target_system; - packet.target_component = target_component; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_UPDATE_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_UPDATE; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_UPDATE_MIN_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_UPDATE_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_UPDATE_CRC); -} - -/** - * @brief Encode a open_drone_id_system_update struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param open_drone_id_system_update C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_open_drone_id_system_update_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_open_drone_id_system_update_t* open_drone_id_system_update) -{ - return mavlink_msg_open_drone_id_system_update_pack(system_id, component_id, msg, open_drone_id_system_update->target_system, open_drone_id_system_update->target_component, open_drone_id_system_update->operator_latitude, open_drone_id_system_update->operator_longitude, open_drone_id_system_update->operator_altitude_geo, open_drone_id_system_update->timestamp); -} - -/** - * @brief Encode a open_drone_id_system_update struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param open_drone_id_system_update C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_open_drone_id_system_update_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_open_drone_id_system_update_t* open_drone_id_system_update) -{ - return mavlink_msg_open_drone_id_system_update_pack_chan(system_id, component_id, chan, msg, open_drone_id_system_update->target_system, open_drone_id_system_update->target_component, open_drone_id_system_update->operator_latitude, open_drone_id_system_update->operator_longitude, open_drone_id_system_update->operator_altitude_geo, open_drone_id_system_update->timestamp); -} - -/** - * @brief Send a open_drone_id_system_update message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID (0 for broadcast). - * @param target_component Component ID (0 for broadcast). - * @param operator_latitude [degE7] Latitude of the operator. If unknown: 0 (both Lat/Lon). - * @param operator_longitude [degE7] Longitude of the operator. If unknown: 0 (both Lat/Lon). - * @param operator_altitude_geo [m] Geodetic altitude of the operator relative to WGS84. If unknown: -1000 m. - * @param timestamp [s] 32 bit Unix Timestamp in seconds since 00:00:00 01/01/2019. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_open_drone_id_system_update_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, int32_t operator_latitude, int32_t operator_longitude, float operator_altitude_geo, uint32_t timestamp) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_UPDATE_LEN]; - _mav_put_int32_t(buf, 0, operator_latitude); - _mav_put_int32_t(buf, 4, operator_longitude); - _mav_put_float(buf, 8, operator_altitude_geo); - _mav_put_uint32_t(buf, 12, timestamp); - _mav_put_uint8_t(buf, 16, target_system); - _mav_put_uint8_t(buf, 17, target_component); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_UPDATE, buf, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_UPDATE_MIN_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_UPDATE_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_UPDATE_CRC); -#else - mavlink_open_drone_id_system_update_t packet; - packet.operator_latitude = operator_latitude; - packet.operator_longitude = operator_longitude; - packet.operator_altitude_geo = operator_altitude_geo; - packet.timestamp = timestamp; - packet.target_system = target_system; - packet.target_component = target_component; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_UPDATE, (const char *)&packet, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_UPDATE_MIN_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_UPDATE_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_UPDATE_CRC); -#endif -} - -/** - * @brief Send a open_drone_id_system_update message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_open_drone_id_system_update_send_struct(mavlink_channel_t chan, const mavlink_open_drone_id_system_update_t* open_drone_id_system_update) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_open_drone_id_system_update_send(chan, open_drone_id_system_update->target_system, open_drone_id_system_update->target_component, open_drone_id_system_update->operator_latitude, open_drone_id_system_update->operator_longitude, open_drone_id_system_update->operator_altitude_geo, open_drone_id_system_update->timestamp); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_UPDATE, (const char *)open_drone_id_system_update, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_UPDATE_MIN_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_UPDATE_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_UPDATE_CRC); -#endif -} - -#if MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_UPDATE_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_open_drone_id_system_update_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, int32_t operator_latitude, int32_t operator_longitude, float operator_altitude_geo, uint32_t timestamp) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_int32_t(buf, 0, operator_latitude); - _mav_put_int32_t(buf, 4, operator_longitude); - _mav_put_float(buf, 8, operator_altitude_geo); - _mav_put_uint32_t(buf, 12, timestamp); - _mav_put_uint8_t(buf, 16, target_system); - _mav_put_uint8_t(buf, 17, target_component); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_UPDATE, buf, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_UPDATE_MIN_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_UPDATE_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_UPDATE_CRC); -#else - mavlink_open_drone_id_system_update_t *packet = (mavlink_open_drone_id_system_update_t *)msgbuf; - packet->operator_latitude = operator_latitude; - packet->operator_longitude = operator_longitude; - packet->operator_altitude_geo = operator_altitude_geo; - packet->timestamp = timestamp; - packet->target_system = target_system; - packet->target_component = target_component; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_UPDATE, (const char *)packet, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_UPDATE_MIN_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_UPDATE_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_UPDATE_CRC); -#endif -} -#endif - -#endif - -// MESSAGE OPEN_DRONE_ID_SYSTEM_UPDATE UNPACKING - - -/** - * @brief Get field target_system from open_drone_id_system_update message - * - * @return System ID (0 for broadcast). - */ -static inline uint8_t mavlink_msg_open_drone_id_system_update_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 16); -} - -/** - * @brief Get field target_component from open_drone_id_system_update message - * - * @return Component ID (0 for broadcast). - */ -static inline uint8_t mavlink_msg_open_drone_id_system_update_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 17); -} - -/** - * @brief Get field operator_latitude from open_drone_id_system_update message - * - * @return [degE7] Latitude of the operator. If unknown: 0 (both Lat/Lon). - */ -static inline int32_t mavlink_msg_open_drone_id_system_update_get_operator_latitude(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 0); -} - -/** - * @brief Get field operator_longitude from open_drone_id_system_update message - * - * @return [degE7] Longitude of the operator. If unknown: 0 (both Lat/Lon). - */ -static inline int32_t mavlink_msg_open_drone_id_system_update_get_operator_longitude(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 4); -} - -/** - * @brief Get field operator_altitude_geo from open_drone_id_system_update message - * - * @return [m] Geodetic altitude of the operator relative to WGS84. If unknown: -1000 m. - */ -static inline float mavlink_msg_open_drone_id_system_update_get_operator_altitude_geo(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field timestamp from open_drone_id_system_update message - * - * @return [s] 32 bit Unix Timestamp in seconds since 00:00:00 01/01/2019. - */ -static inline uint32_t mavlink_msg_open_drone_id_system_update_get_timestamp(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 12); -} - -/** - * @brief Decode a open_drone_id_system_update message into a struct - * - * @param msg The message to decode - * @param open_drone_id_system_update C-struct to decode the message contents into - */ -static inline void mavlink_msg_open_drone_id_system_update_decode(const mavlink_message_t* msg, mavlink_open_drone_id_system_update_t* open_drone_id_system_update) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - open_drone_id_system_update->operator_latitude = mavlink_msg_open_drone_id_system_update_get_operator_latitude(msg); - open_drone_id_system_update->operator_longitude = mavlink_msg_open_drone_id_system_update_get_operator_longitude(msg); - open_drone_id_system_update->operator_altitude_geo = mavlink_msg_open_drone_id_system_update_get_operator_altitude_geo(msg); - open_drone_id_system_update->timestamp = mavlink_msg_open_drone_id_system_update_get_timestamp(msg); - open_drone_id_system_update->target_system = mavlink_msg_open_drone_id_system_update_get_target_system(msg); - open_drone_id_system_update->target_component = mavlink_msg_open_drone_id_system_update_get_target_component(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_UPDATE_LEN? msg->len : MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_UPDATE_LEN; - memset(open_drone_id_system_update, 0, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_UPDATE_LEN); - memcpy(open_drone_id_system_update, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_optical_flow.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_optical_flow.h deleted file mode 100644 index 0c414a84..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_optical_flow.h +++ /dev/null @@ -1,438 +0,0 @@ -#pragma once -// MESSAGE OPTICAL_FLOW PACKING - -#define MAVLINK_MSG_ID_OPTICAL_FLOW 100 - -MAVPACKED( -typedef struct __mavlink_optical_flow_t { - uint64_t time_usec; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/ - float flow_comp_m_x; /*< [m/s] Flow in x-sensor direction, angular-speed compensated*/ - float flow_comp_m_y; /*< [m/s] Flow in y-sensor direction, angular-speed compensated*/ - float ground_distance; /*< [m] Ground distance. Positive value: distance known. Negative value: Unknown distance*/ - int16_t flow_x; /*< [dpix] Flow in x-sensor direction*/ - int16_t flow_y; /*< [dpix] Flow in y-sensor direction*/ - uint8_t sensor_id; /*< Sensor ID*/ - uint8_t quality; /*< Optical flow quality / confidence. 0: bad, 255: maximum quality*/ - float flow_rate_x; /*< [rad/s] Flow rate about X axis*/ - float flow_rate_y; /*< [rad/s] Flow rate about Y axis*/ -}) mavlink_optical_flow_t; - -#define MAVLINK_MSG_ID_OPTICAL_FLOW_LEN 34 -#define MAVLINK_MSG_ID_OPTICAL_FLOW_MIN_LEN 26 -#define MAVLINK_MSG_ID_100_LEN 34 -#define MAVLINK_MSG_ID_100_MIN_LEN 26 - -#define MAVLINK_MSG_ID_OPTICAL_FLOW_CRC 175 -#define MAVLINK_MSG_ID_100_CRC 175 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_OPTICAL_FLOW { \ - 100, \ - "OPTICAL_FLOW", \ - 10, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_optical_flow_t, time_usec) }, \ - { "sensor_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_optical_flow_t, sensor_id) }, \ - { "flow_x", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_optical_flow_t, flow_x) }, \ - { "flow_y", NULL, MAVLINK_TYPE_INT16_T, 0, 22, offsetof(mavlink_optical_flow_t, flow_y) }, \ - { "flow_comp_m_x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_optical_flow_t, flow_comp_m_x) }, \ - { "flow_comp_m_y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_optical_flow_t, flow_comp_m_y) }, \ - { "quality", NULL, MAVLINK_TYPE_UINT8_T, 0, 25, offsetof(mavlink_optical_flow_t, quality) }, \ - { "ground_distance", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_optical_flow_t, ground_distance) }, \ - { "flow_rate_x", NULL, MAVLINK_TYPE_FLOAT, 0, 26, offsetof(mavlink_optical_flow_t, flow_rate_x) }, \ - { "flow_rate_y", NULL, MAVLINK_TYPE_FLOAT, 0, 30, offsetof(mavlink_optical_flow_t, flow_rate_y) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_OPTICAL_FLOW { \ - "OPTICAL_FLOW", \ - 10, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_optical_flow_t, time_usec) }, \ - { "sensor_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_optical_flow_t, sensor_id) }, \ - { "flow_x", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_optical_flow_t, flow_x) }, \ - { "flow_y", NULL, MAVLINK_TYPE_INT16_T, 0, 22, offsetof(mavlink_optical_flow_t, flow_y) }, \ - { "flow_comp_m_x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_optical_flow_t, flow_comp_m_x) }, \ - { "flow_comp_m_y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_optical_flow_t, flow_comp_m_y) }, \ - { "quality", NULL, MAVLINK_TYPE_UINT8_T, 0, 25, offsetof(mavlink_optical_flow_t, quality) }, \ - { "ground_distance", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_optical_flow_t, ground_distance) }, \ - { "flow_rate_x", NULL, MAVLINK_TYPE_FLOAT, 0, 26, offsetof(mavlink_optical_flow_t, flow_rate_x) }, \ - { "flow_rate_y", NULL, MAVLINK_TYPE_FLOAT, 0, 30, offsetof(mavlink_optical_flow_t, flow_rate_y) }, \ - } \ -} -#endif - -/** - * @brief Pack a optical_flow message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @param sensor_id Sensor ID - * @param flow_x [dpix] Flow in x-sensor direction - * @param flow_y [dpix] Flow in y-sensor direction - * @param flow_comp_m_x [m/s] Flow in x-sensor direction, angular-speed compensated - * @param flow_comp_m_y [m/s] Flow in y-sensor direction, angular-speed compensated - * @param quality Optical flow quality / confidence. 0: bad, 255: maximum quality - * @param ground_distance [m] Ground distance. Positive value: distance known. Negative value: Unknown distance - * @param flow_rate_x [rad/s] Flow rate about X axis - * @param flow_rate_y [rad/s] Flow rate about Y axis - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_optical_flow_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint64_t time_usec, uint8_t sensor_id, int16_t flow_x, int16_t flow_y, float flow_comp_m_x, float flow_comp_m_y, uint8_t quality, float ground_distance, float flow_rate_x, float flow_rate_y) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_OPTICAL_FLOW_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, flow_comp_m_x); - _mav_put_float(buf, 12, flow_comp_m_y); - _mav_put_float(buf, 16, ground_distance); - _mav_put_int16_t(buf, 20, flow_x); - _mav_put_int16_t(buf, 22, flow_y); - _mav_put_uint8_t(buf, 24, sensor_id); - _mav_put_uint8_t(buf, 25, quality); - _mav_put_float(buf, 26, flow_rate_x); - _mav_put_float(buf, 30, flow_rate_y); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN); -#else - mavlink_optical_flow_t packet; - packet.time_usec = time_usec; - packet.flow_comp_m_x = flow_comp_m_x; - packet.flow_comp_m_y = flow_comp_m_y; - packet.ground_distance = ground_distance; - packet.flow_x = flow_x; - packet.flow_y = flow_y; - packet.sensor_id = sensor_id; - packet.quality = quality; - packet.flow_rate_x = flow_rate_x; - packet.flow_rate_y = flow_rate_y; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_OPTICAL_FLOW; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_OPTICAL_FLOW_MIN_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_CRC); -} - -/** - * @brief Pack a optical_flow message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @param sensor_id Sensor ID - * @param flow_x [dpix] Flow in x-sensor direction - * @param flow_y [dpix] Flow in y-sensor direction - * @param flow_comp_m_x [m/s] Flow in x-sensor direction, angular-speed compensated - * @param flow_comp_m_y [m/s] Flow in y-sensor direction, angular-speed compensated - * @param quality Optical flow quality / confidence. 0: bad, 255: maximum quality - * @param ground_distance [m] Ground distance. Positive value: distance known. Negative value: Unknown distance - * @param flow_rate_x [rad/s] Flow rate about X axis - * @param flow_rate_y [rad/s] Flow rate about Y axis - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_optical_flow_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint64_t time_usec,uint8_t sensor_id,int16_t flow_x,int16_t flow_y,float flow_comp_m_x,float flow_comp_m_y,uint8_t quality,float ground_distance,float flow_rate_x,float flow_rate_y) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_OPTICAL_FLOW_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, flow_comp_m_x); - _mav_put_float(buf, 12, flow_comp_m_y); - _mav_put_float(buf, 16, ground_distance); - _mav_put_int16_t(buf, 20, flow_x); - _mav_put_int16_t(buf, 22, flow_y); - _mav_put_uint8_t(buf, 24, sensor_id); - _mav_put_uint8_t(buf, 25, quality); - _mav_put_float(buf, 26, flow_rate_x); - _mav_put_float(buf, 30, flow_rate_y); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN); -#else - mavlink_optical_flow_t packet; - packet.time_usec = time_usec; - packet.flow_comp_m_x = flow_comp_m_x; - packet.flow_comp_m_y = flow_comp_m_y; - packet.ground_distance = ground_distance; - packet.flow_x = flow_x; - packet.flow_y = flow_y; - packet.sensor_id = sensor_id; - packet.quality = quality; - packet.flow_rate_x = flow_rate_x; - packet.flow_rate_y = flow_rate_y; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_OPTICAL_FLOW; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_OPTICAL_FLOW_MIN_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_CRC); -} - -/** - * @brief Encode a optical_flow struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param optical_flow C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_optical_flow_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_optical_flow_t* optical_flow) -{ - return mavlink_msg_optical_flow_pack(system_id, component_id, msg, optical_flow->time_usec, optical_flow->sensor_id, optical_flow->flow_x, optical_flow->flow_y, optical_flow->flow_comp_m_x, optical_flow->flow_comp_m_y, optical_flow->quality, optical_flow->ground_distance, optical_flow->flow_rate_x, optical_flow->flow_rate_y); -} - -/** - * @brief Encode a optical_flow struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param optical_flow C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_optical_flow_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_optical_flow_t* optical_flow) -{ - return mavlink_msg_optical_flow_pack_chan(system_id, component_id, chan, msg, optical_flow->time_usec, optical_flow->sensor_id, optical_flow->flow_x, optical_flow->flow_y, optical_flow->flow_comp_m_x, optical_flow->flow_comp_m_y, optical_flow->quality, optical_flow->ground_distance, optical_flow->flow_rate_x, optical_flow->flow_rate_y); -} - -/** - * @brief Send a optical_flow message - * @param chan MAVLink channel to send the message - * - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @param sensor_id Sensor ID - * @param flow_x [dpix] Flow in x-sensor direction - * @param flow_y [dpix] Flow in y-sensor direction - * @param flow_comp_m_x [m/s] Flow in x-sensor direction, angular-speed compensated - * @param flow_comp_m_y [m/s] Flow in y-sensor direction, angular-speed compensated - * @param quality Optical flow quality / confidence. 0: bad, 255: maximum quality - * @param ground_distance [m] Ground distance. Positive value: distance known. Negative value: Unknown distance - * @param flow_rate_x [rad/s] Flow rate about X axis - * @param flow_rate_y [rad/s] Flow rate about Y axis - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_optical_flow_send(mavlink_channel_t chan, uint64_t time_usec, uint8_t sensor_id, int16_t flow_x, int16_t flow_y, float flow_comp_m_x, float flow_comp_m_y, uint8_t quality, float ground_distance, float flow_rate_x, float flow_rate_y) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_OPTICAL_FLOW_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, flow_comp_m_x); - _mav_put_float(buf, 12, flow_comp_m_y); - _mav_put_float(buf, 16, ground_distance); - _mav_put_int16_t(buf, 20, flow_x); - _mav_put_int16_t(buf, 22, flow_y); - _mav_put_uint8_t(buf, 24, sensor_id); - _mav_put_uint8_t(buf, 25, quality); - _mav_put_float(buf, 26, flow_rate_x); - _mav_put_float(buf, 30, flow_rate_y); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPTICAL_FLOW, buf, MAVLINK_MSG_ID_OPTICAL_FLOW_MIN_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_CRC); -#else - mavlink_optical_flow_t packet; - packet.time_usec = time_usec; - packet.flow_comp_m_x = flow_comp_m_x; - packet.flow_comp_m_y = flow_comp_m_y; - packet.ground_distance = ground_distance; - packet.flow_x = flow_x; - packet.flow_y = flow_y; - packet.sensor_id = sensor_id; - packet.quality = quality; - packet.flow_rate_x = flow_rate_x; - packet.flow_rate_y = flow_rate_y; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPTICAL_FLOW, (const char *)&packet, MAVLINK_MSG_ID_OPTICAL_FLOW_MIN_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_CRC); -#endif -} - -/** - * @brief Send a optical_flow message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_optical_flow_send_struct(mavlink_channel_t chan, const mavlink_optical_flow_t* optical_flow) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_optical_flow_send(chan, optical_flow->time_usec, optical_flow->sensor_id, optical_flow->flow_x, optical_flow->flow_y, optical_flow->flow_comp_m_x, optical_flow->flow_comp_m_y, optical_flow->quality, optical_flow->ground_distance, optical_flow->flow_rate_x, optical_flow->flow_rate_y); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPTICAL_FLOW, (const char *)optical_flow, MAVLINK_MSG_ID_OPTICAL_FLOW_MIN_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_CRC); -#endif -} - -#if MAVLINK_MSG_ID_OPTICAL_FLOW_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_optical_flow_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, uint8_t sensor_id, int16_t flow_x, int16_t flow_y, float flow_comp_m_x, float flow_comp_m_y, uint8_t quality, float ground_distance, float flow_rate_x, float flow_rate_y) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, flow_comp_m_x); - _mav_put_float(buf, 12, flow_comp_m_y); - _mav_put_float(buf, 16, ground_distance); - _mav_put_int16_t(buf, 20, flow_x); - _mav_put_int16_t(buf, 22, flow_y); - _mav_put_uint8_t(buf, 24, sensor_id); - _mav_put_uint8_t(buf, 25, quality); - _mav_put_float(buf, 26, flow_rate_x); - _mav_put_float(buf, 30, flow_rate_y); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPTICAL_FLOW, buf, MAVLINK_MSG_ID_OPTICAL_FLOW_MIN_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_CRC); -#else - mavlink_optical_flow_t *packet = (mavlink_optical_flow_t *)msgbuf; - packet->time_usec = time_usec; - packet->flow_comp_m_x = flow_comp_m_x; - packet->flow_comp_m_y = flow_comp_m_y; - packet->ground_distance = ground_distance; - packet->flow_x = flow_x; - packet->flow_y = flow_y; - packet->sensor_id = sensor_id; - packet->quality = quality; - packet->flow_rate_x = flow_rate_x; - packet->flow_rate_y = flow_rate_y; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPTICAL_FLOW, (const char *)packet, MAVLINK_MSG_ID_OPTICAL_FLOW_MIN_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_CRC); -#endif -} -#endif - -#endif - -// MESSAGE OPTICAL_FLOW UNPACKING - - -/** - * @brief Get field time_usec from optical_flow message - * - * @return [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - */ -static inline uint64_t mavlink_msg_optical_flow_get_time_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field sensor_id from optical_flow message - * - * @return Sensor ID - */ -static inline uint8_t mavlink_msg_optical_flow_get_sensor_id(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 24); -} - -/** - * @brief Get field flow_x from optical_flow message - * - * @return [dpix] Flow in x-sensor direction - */ -static inline int16_t mavlink_msg_optical_flow_get_flow_x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 20); -} - -/** - * @brief Get field flow_y from optical_flow message - * - * @return [dpix] Flow in y-sensor direction - */ -static inline int16_t mavlink_msg_optical_flow_get_flow_y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 22); -} - -/** - * @brief Get field flow_comp_m_x from optical_flow message - * - * @return [m/s] Flow in x-sensor direction, angular-speed compensated - */ -static inline float mavlink_msg_optical_flow_get_flow_comp_m_x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field flow_comp_m_y from optical_flow message - * - * @return [m/s] Flow in y-sensor direction, angular-speed compensated - */ -static inline float mavlink_msg_optical_flow_get_flow_comp_m_y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field quality from optical_flow message - * - * @return Optical flow quality / confidence. 0: bad, 255: maximum quality - */ -static inline uint8_t mavlink_msg_optical_flow_get_quality(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 25); -} - -/** - * @brief Get field ground_distance from optical_flow message - * - * @return [m] Ground distance. Positive value: distance known. Negative value: Unknown distance - */ -static inline float mavlink_msg_optical_flow_get_ground_distance(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field flow_rate_x from optical_flow message - * - * @return [rad/s] Flow rate about X axis - */ -static inline float mavlink_msg_optical_flow_get_flow_rate_x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 26); -} - -/** - * @brief Get field flow_rate_y from optical_flow message - * - * @return [rad/s] Flow rate about Y axis - */ -static inline float mavlink_msg_optical_flow_get_flow_rate_y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 30); -} - -/** - * @brief Decode a optical_flow message into a struct - * - * @param msg The message to decode - * @param optical_flow C-struct to decode the message contents into - */ -static inline void mavlink_msg_optical_flow_decode(const mavlink_message_t* msg, mavlink_optical_flow_t* optical_flow) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - optical_flow->time_usec = mavlink_msg_optical_flow_get_time_usec(msg); - optical_flow->flow_comp_m_x = mavlink_msg_optical_flow_get_flow_comp_m_x(msg); - optical_flow->flow_comp_m_y = mavlink_msg_optical_flow_get_flow_comp_m_y(msg); - optical_flow->ground_distance = mavlink_msg_optical_flow_get_ground_distance(msg); - optical_flow->flow_x = mavlink_msg_optical_flow_get_flow_x(msg); - optical_flow->flow_y = mavlink_msg_optical_flow_get_flow_y(msg); - optical_flow->sensor_id = mavlink_msg_optical_flow_get_sensor_id(msg); - optical_flow->quality = mavlink_msg_optical_flow_get_quality(msg); - optical_flow->flow_rate_x = mavlink_msg_optical_flow_get_flow_rate_x(msg); - optical_flow->flow_rate_y = mavlink_msg_optical_flow_get_flow_rate_y(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_OPTICAL_FLOW_LEN? msg->len : MAVLINK_MSG_ID_OPTICAL_FLOW_LEN; - memset(optical_flow, 0, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN); - memcpy(optical_flow, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_optical_flow_rad.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_optical_flow_rad.h deleted file mode 100644 index a8065dce..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_optical_flow_rad.h +++ /dev/null @@ -1,488 +0,0 @@ -#pragma once -// MESSAGE OPTICAL_FLOW_RAD PACKING - -#define MAVLINK_MSG_ID_OPTICAL_FLOW_RAD 106 - - -typedef struct __mavlink_optical_flow_rad_t { - uint64_t time_usec; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/ - uint32_t integration_time_us; /*< [us] Integration time. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the.*/ - float integrated_x; /*< [rad] Flow around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.)*/ - float integrated_y; /*< [rad] Flow around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.)*/ - float integrated_xgyro; /*< [rad] RH rotation around X axis*/ - float integrated_ygyro; /*< [rad] RH rotation around Y axis*/ - float integrated_zgyro; /*< [rad] RH rotation around Z axis*/ - uint32_t time_delta_distance_us; /*< [us] Time since the distance was sampled.*/ - float distance; /*< [m] Distance to the center of the flow field. Positive value (including zero): distance known. Negative value: Unknown distance.*/ - int16_t temperature; /*< [cdegC] Temperature*/ - uint8_t sensor_id; /*< Sensor ID*/ - uint8_t quality; /*< Optical flow quality / confidence. 0: no valid flow, 255: maximum quality*/ -} mavlink_optical_flow_rad_t; - -#define MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN 44 -#define MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_MIN_LEN 44 -#define MAVLINK_MSG_ID_106_LEN 44 -#define MAVLINK_MSG_ID_106_MIN_LEN 44 - -#define MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_CRC 138 -#define MAVLINK_MSG_ID_106_CRC 138 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_OPTICAL_FLOW_RAD { \ - 106, \ - "OPTICAL_FLOW_RAD", \ - 12, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_optical_flow_rad_t, time_usec) }, \ - { "sensor_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 42, offsetof(mavlink_optical_flow_rad_t, sensor_id) }, \ - { "integration_time_us", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_optical_flow_rad_t, integration_time_us) }, \ - { "integrated_x", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_optical_flow_rad_t, integrated_x) }, \ - { "integrated_y", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_optical_flow_rad_t, integrated_y) }, \ - { "integrated_xgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_optical_flow_rad_t, integrated_xgyro) }, \ - { "integrated_ygyro", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_optical_flow_rad_t, integrated_ygyro) }, \ - { "integrated_zgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_optical_flow_rad_t, integrated_zgyro) }, \ - { "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 40, offsetof(mavlink_optical_flow_rad_t, temperature) }, \ - { "quality", NULL, MAVLINK_TYPE_UINT8_T, 0, 43, offsetof(mavlink_optical_flow_rad_t, quality) }, \ - { "time_delta_distance_us", NULL, MAVLINK_TYPE_UINT32_T, 0, 32, offsetof(mavlink_optical_flow_rad_t, time_delta_distance_us) }, \ - { "distance", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_optical_flow_rad_t, distance) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_OPTICAL_FLOW_RAD { \ - "OPTICAL_FLOW_RAD", \ - 12, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_optical_flow_rad_t, time_usec) }, \ - { "sensor_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 42, offsetof(mavlink_optical_flow_rad_t, sensor_id) }, \ - { "integration_time_us", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_optical_flow_rad_t, integration_time_us) }, \ - { "integrated_x", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_optical_flow_rad_t, integrated_x) }, \ - { "integrated_y", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_optical_flow_rad_t, integrated_y) }, \ - { "integrated_xgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_optical_flow_rad_t, integrated_xgyro) }, \ - { "integrated_ygyro", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_optical_flow_rad_t, integrated_ygyro) }, \ - { "integrated_zgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_optical_flow_rad_t, integrated_zgyro) }, \ - { "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 40, offsetof(mavlink_optical_flow_rad_t, temperature) }, \ - { "quality", NULL, MAVLINK_TYPE_UINT8_T, 0, 43, offsetof(mavlink_optical_flow_rad_t, quality) }, \ - { "time_delta_distance_us", NULL, MAVLINK_TYPE_UINT32_T, 0, 32, offsetof(mavlink_optical_flow_rad_t, time_delta_distance_us) }, \ - { "distance", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_optical_flow_rad_t, distance) }, \ - } \ -} -#endif - -/** - * @brief Pack a optical_flow_rad message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @param sensor_id Sensor ID - * @param integration_time_us [us] Integration time. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the. - * @param integrated_x [rad] Flow around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.) - * @param integrated_y [rad] Flow around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.) - * @param integrated_xgyro [rad] RH rotation around X axis - * @param integrated_ygyro [rad] RH rotation around Y axis - * @param integrated_zgyro [rad] RH rotation around Z axis - * @param temperature [cdegC] Temperature - * @param quality Optical flow quality / confidence. 0: no valid flow, 255: maximum quality - * @param time_delta_distance_us [us] Time since the distance was sampled. - * @param distance [m] Distance to the center of the flow field. Positive value (including zero): distance known. Negative value: Unknown distance. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_optical_flow_rad_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint64_t time_usec, uint8_t sensor_id, uint32_t integration_time_us, float integrated_x, float integrated_y, float integrated_xgyro, float integrated_ygyro, float integrated_zgyro, int16_t temperature, uint8_t quality, uint32_t time_delta_distance_us, float distance) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint32_t(buf, 8, integration_time_us); - _mav_put_float(buf, 12, integrated_x); - _mav_put_float(buf, 16, integrated_y); - _mav_put_float(buf, 20, integrated_xgyro); - _mav_put_float(buf, 24, integrated_ygyro); - _mav_put_float(buf, 28, integrated_zgyro); - _mav_put_uint32_t(buf, 32, time_delta_distance_us); - _mav_put_float(buf, 36, distance); - _mav_put_int16_t(buf, 40, temperature); - _mav_put_uint8_t(buf, 42, sensor_id); - _mav_put_uint8_t(buf, 43, quality); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN); -#else - mavlink_optical_flow_rad_t packet; - packet.time_usec = time_usec; - packet.integration_time_us = integration_time_us; - packet.integrated_x = integrated_x; - packet.integrated_y = integrated_y; - packet.integrated_xgyro = integrated_xgyro; - packet.integrated_ygyro = integrated_ygyro; - packet.integrated_zgyro = integrated_zgyro; - packet.time_delta_distance_us = time_delta_distance_us; - packet.distance = distance; - packet.temperature = temperature; - packet.sensor_id = sensor_id; - packet.quality = quality; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_OPTICAL_FLOW_RAD; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_MIN_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_CRC); -} - -/** - * @brief Pack a optical_flow_rad message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @param sensor_id Sensor ID - * @param integration_time_us [us] Integration time. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the. - * @param integrated_x [rad] Flow around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.) - * @param integrated_y [rad] Flow around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.) - * @param integrated_xgyro [rad] RH rotation around X axis - * @param integrated_ygyro [rad] RH rotation around Y axis - * @param integrated_zgyro [rad] RH rotation around Z axis - * @param temperature [cdegC] Temperature - * @param quality Optical flow quality / confidence. 0: no valid flow, 255: maximum quality - * @param time_delta_distance_us [us] Time since the distance was sampled. - * @param distance [m] Distance to the center of the flow field. Positive value (including zero): distance known. Negative value: Unknown distance. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_optical_flow_rad_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint64_t time_usec,uint8_t sensor_id,uint32_t integration_time_us,float integrated_x,float integrated_y,float integrated_xgyro,float integrated_ygyro,float integrated_zgyro,int16_t temperature,uint8_t quality,uint32_t time_delta_distance_us,float distance) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint32_t(buf, 8, integration_time_us); - _mav_put_float(buf, 12, integrated_x); - _mav_put_float(buf, 16, integrated_y); - _mav_put_float(buf, 20, integrated_xgyro); - _mav_put_float(buf, 24, integrated_ygyro); - _mav_put_float(buf, 28, integrated_zgyro); - _mav_put_uint32_t(buf, 32, time_delta_distance_us); - _mav_put_float(buf, 36, distance); - _mav_put_int16_t(buf, 40, temperature); - _mav_put_uint8_t(buf, 42, sensor_id); - _mav_put_uint8_t(buf, 43, quality); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN); -#else - mavlink_optical_flow_rad_t packet; - packet.time_usec = time_usec; - packet.integration_time_us = integration_time_us; - packet.integrated_x = integrated_x; - packet.integrated_y = integrated_y; - packet.integrated_xgyro = integrated_xgyro; - packet.integrated_ygyro = integrated_ygyro; - packet.integrated_zgyro = integrated_zgyro; - packet.time_delta_distance_us = time_delta_distance_us; - packet.distance = distance; - packet.temperature = temperature; - packet.sensor_id = sensor_id; - packet.quality = quality; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_OPTICAL_FLOW_RAD; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_MIN_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_CRC); -} - -/** - * @brief Encode a optical_flow_rad struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param optical_flow_rad C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_optical_flow_rad_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_optical_flow_rad_t* optical_flow_rad) -{ - return mavlink_msg_optical_flow_rad_pack(system_id, component_id, msg, optical_flow_rad->time_usec, optical_flow_rad->sensor_id, optical_flow_rad->integration_time_us, optical_flow_rad->integrated_x, optical_flow_rad->integrated_y, optical_flow_rad->integrated_xgyro, optical_flow_rad->integrated_ygyro, optical_flow_rad->integrated_zgyro, optical_flow_rad->temperature, optical_flow_rad->quality, optical_flow_rad->time_delta_distance_us, optical_flow_rad->distance); -} - -/** - * @brief Encode a optical_flow_rad struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param optical_flow_rad C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_optical_flow_rad_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_optical_flow_rad_t* optical_flow_rad) -{ - return mavlink_msg_optical_flow_rad_pack_chan(system_id, component_id, chan, msg, optical_flow_rad->time_usec, optical_flow_rad->sensor_id, optical_flow_rad->integration_time_us, optical_flow_rad->integrated_x, optical_flow_rad->integrated_y, optical_flow_rad->integrated_xgyro, optical_flow_rad->integrated_ygyro, optical_flow_rad->integrated_zgyro, optical_flow_rad->temperature, optical_flow_rad->quality, optical_flow_rad->time_delta_distance_us, optical_flow_rad->distance); -} - -/** - * @brief Send a optical_flow_rad message - * @param chan MAVLink channel to send the message - * - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @param sensor_id Sensor ID - * @param integration_time_us [us] Integration time. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the. - * @param integrated_x [rad] Flow around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.) - * @param integrated_y [rad] Flow around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.) - * @param integrated_xgyro [rad] RH rotation around X axis - * @param integrated_ygyro [rad] RH rotation around Y axis - * @param integrated_zgyro [rad] RH rotation around Z axis - * @param temperature [cdegC] Temperature - * @param quality Optical flow quality / confidence. 0: no valid flow, 255: maximum quality - * @param time_delta_distance_us [us] Time since the distance was sampled. - * @param distance [m] Distance to the center of the flow field. Positive value (including zero): distance known. Negative value: Unknown distance. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_optical_flow_rad_send(mavlink_channel_t chan, uint64_t time_usec, uint8_t sensor_id, uint32_t integration_time_us, float integrated_x, float integrated_y, float integrated_xgyro, float integrated_ygyro, float integrated_zgyro, int16_t temperature, uint8_t quality, uint32_t time_delta_distance_us, float distance) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint32_t(buf, 8, integration_time_us); - _mav_put_float(buf, 12, integrated_x); - _mav_put_float(buf, 16, integrated_y); - _mav_put_float(buf, 20, integrated_xgyro); - _mav_put_float(buf, 24, integrated_ygyro); - _mav_put_float(buf, 28, integrated_zgyro); - _mav_put_uint32_t(buf, 32, time_delta_distance_us); - _mav_put_float(buf, 36, distance); - _mav_put_int16_t(buf, 40, temperature); - _mav_put_uint8_t(buf, 42, sensor_id); - _mav_put_uint8_t(buf, 43, quality); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD, buf, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_MIN_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_CRC); -#else - mavlink_optical_flow_rad_t packet; - packet.time_usec = time_usec; - packet.integration_time_us = integration_time_us; - packet.integrated_x = integrated_x; - packet.integrated_y = integrated_y; - packet.integrated_xgyro = integrated_xgyro; - packet.integrated_ygyro = integrated_ygyro; - packet.integrated_zgyro = integrated_zgyro; - packet.time_delta_distance_us = time_delta_distance_us; - packet.distance = distance; - packet.temperature = temperature; - packet.sensor_id = sensor_id; - packet.quality = quality; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD, (const char *)&packet, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_MIN_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_CRC); -#endif -} - -/** - * @brief Send a optical_flow_rad message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_optical_flow_rad_send_struct(mavlink_channel_t chan, const mavlink_optical_flow_rad_t* optical_flow_rad) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_optical_flow_rad_send(chan, optical_flow_rad->time_usec, optical_flow_rad->sensor_id, optical_flow_rad->integration_time_us, optical_flow_rad->integrated_x, optical_flow_rad->integrated_y, optical_flow_rad->integrated_xgyro, optical_flow_rad->integrated_ygyro, optical_flow_rad->integrated_zgyro, optical_flow_rad->temperature, optical_flow_rad->quality, optical_flow_rad->time_delta_distance_us, optical_flow_rad->distance); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD, (const char *)optical_flow_rad, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_MIN_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_CRC); -#endif -} - -#if MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_optical_flow_rad_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, uint8_t sensor_id, uint32_t integration_time_us, float integrated_x, float integrated_y, float integrated_xgyro, float integrated_ygyro, float integrated_zgyro, int16_t temperature, uint8_t quality, uint32_t time_delta_distance_us, float distance) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint32_t(buf, 8, integration_time_us); - _mav_put_float(buf, 12, integrated_x); - _mav_put_float(buf, 16, integrated_y); - _mav_put_float(buf, 20, integrated_xgyro); - _mav_put_float(buf, 24, integrated_ygyro); - _mav_put_float(buf, 28, integrated_zgyro); - _mav_put_uint32_t(buf, 32, time_delta_distance_us); - _mav_put_float(buf, 36, distance); - _mav_put_int16_t(buf, 40, temperature); - _mav_put_uint8_t(buf, 42, sensor_id); - _mav_put_uint8_t(buf, 43, quality); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD, buf, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_MIN_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_CRC); -#else - mavlink_optical_flow_rad_t *packet = (mavlink_optical_flow_rad_t *)msgbuf; - packet->time_usec = time_usec; - packet->integration_time_us = integration_time_us; - packet->integrated_x = integrated_x; - packet->integrated_y = integrated_y; - packet->integrated_xgyro = integrated_xgyro; - packet->integrated_ygyro = integrated_ygyro; - packet->integrated_zgyro = integrated_zgyro; - packet->time_delta_distance_us = time_delta_distance_us; - packet->distance = distance; - packet->temperature = temperature; - packet->sensor_id = sensor_id; - packet->quality = quality; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD, (const char *)packet, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_MIN_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_CRC); -#endif -} -#endif - -#endif - -// MESSAGE OPTICAL_FLOW_RAD UNPACKING - - -/** - * @brief Get field time_usec from optical_flow_rad message - * - * @return [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - */ -static inline uint64_t mavlink_msg_optical_flow_rad_get_time_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field sensor_id from optical_flow_rad message - * - * @return Sensor ID - */ -static inline uint8_t mavlink_msg_optical_flow_rad_get_sensor_id(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 42); -} - -/** - * @brief Get field integration_time_us from optical_flow_rad message - * - * @return [us] Integration time. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the. - */ -static inline uint32_t mavlink_msg_optical_flow_rad_get_integration_time_us(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 8); -} - -/** - * @brief Get field integrated_x from optical_flow_rad message - * - * @return [rad] Flow around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.) - */ -static inline float mavlink_msg_optical_flow_rad_get_integrated_x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field integrated_y from optical_flow_rad message - * - * @return [rad] Flow around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.) - */ -static inline float mavlink_msg_optical_flow_rad_get_integrated_y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field integrated_xgyro from optical_flow_rad message - * - * @return [rad] RH rotation around X axis - */ -static inline float mavlink_msg_optical_flow_rad_get_integrated_xgyro(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Get field integrated_ygyro from optical_flow_rad message - * - * @return [rad] RH rotation around Y axis - */ -static inline float mavlink_msg_optical_flow_rad_get_integrated_ygyro(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Get field integrated_zgyro from optical_flow_rad message - * - * @return [rad] RH rotation around Z axis - */ -static inline float mavlink_msg_optical_flow_rad_get_integrated_zgyro(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 28); -} - -/** - * @brief Get field temperature from optical_flow_rad message - * - * @return [cdegC] Temperature - */ -static inline int16_t mavlink_msg_optical_flow_rad_get_temperature(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 40); -} - -/** - * @brief Get field quality from optical_flow_rad message - * - * @return Optical flow quality / confidence. 0: no valid flow, 255: maximum quality - */ -static inline uint8_t mavlink_msg_optical_flow_rad_get_quality(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 43); -} - -/** - * @brief Get field time_delta_distance_us from optical_flow_rad message - * - * @return [us] Time since the distance was sampled. - */ -static inline uint32_t mavlink_msg_optical_flow_rad_get_time_delta_distance_us(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 32); -} - -/** - * @brief Get field distance from optical_flow_rad message - * - * @return [m] Distance to the center of the flow field. Positive value (including zero): distance known. Negative value: Unknown distance. - */ -static inline float mavlink_msg_optical_flow_rad_get_distance(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 36); -} - -/** - * @brief Decode a optical_flow_rad message into a struct - * - * @param msg The message to decode - * @param optical_flow_rad C-struct to decode the message contents into - */ -static inline void mavlink_msg_optical_flow_rad_decode(const mavlink_message_t* msg, mavlink_optical_flow_rad_t* optical_flow_rad) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - optical_flow_rad->time_usec = mavlink_msg_optical_flow_rad_get_time_usec(msg); - optical_flow_rad->integration_time_us = mavlink_msg_optical_flow_rad_get_integration_time_us(msg); - optical_flow_rad->integrated_x = mavlink_msg_optical_flow_rad_get_integrated_x(msg); - optical_flow_rad->integrated_y = mavlink_msg_optical_flow_rad_get_integrated_y(msg); - optical_flow_rad->integrated_xgyro = mavlink_msg_optical_flow_rad_get_integrated_xgyro(msg); - optical_flow_rad->integrated_ygyro = mavlink_msg_optical_flow_rad_get_integrated_ygyro(msg); - optical_flow_rad->integrated_zgyro = mavlink_msg_optical_flow_rad_get_integrated_zgyro(msg); - optical_flow_rad->time_delta_distance_us = mavlink_msg_optical_flow_rad_get_time_delta_distance_us(msg); - optical_flow_rad->distance = mavlink_msg_optical_flow_rad_get_distance(msg); - optical_flow_rad->temperature = mavlink_msg_optical_flow_rad_get_temperature(msg); - optical_flow_rad->sensor_id = mavlink_msg_optical_flow_rad_get_sensor_id(msg); - optical_flow_rad->quality = mavlink_msg_optical_flow_rad_get_quality(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN? msg->len : MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN; - memset(optical_flow_rad, 0, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN); - memcpy(optical_flow_rad, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_orbit_execution_status.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_orbit_execution_status.h deleted file mode 100644 index d5d9f3b1..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_orbit_execution_status.h +++ /dev/null @@ -1,338 +0,0 @@ -#pragma once -// MESSAGE ORBIT_EXECUTION_STATUS PACKING - -#define MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS 360 - - -typedef struct __mavlink_orbit_execution_status_t { - uint64_t time_usec; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/ - float radius; /*< [m] Radius of the orbit circle. Positive values orbit clockwise, negative values orbit counter-clockwise.*/ - int32_t x; /*< X coordinate of center point. Coordinate system depends on frame field: local = x position in meters * 1e4, global = latitude in degrees * 1e7.*/ - int32_t y; /*< Y coordinate of center point. Coordinate system depends on frame field: local = x position in meters * 1e4, global = latitude in degrees * 1e7.*/ - float z; /*< [m] Altitude of center point. Coordinate system depends on frame field.*/ - uint8_t frame; /*< The coordinate system of the fields: x, y, z.*/ -} mavlink_orbit_execution_status_t; - -#define MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS_LEN 25 -#define MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS_MIN_LEN 25 -#define MAVLINK_MSG_ID_360_LEN 25 -#define MAVLINK_MSG_ID_360_MIN_LEN 25 - -#define MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS_CRC 11 -#define MAVLINK_MSG_ID_360_CRC 11 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_ORBIT_EXECUTION_STATUS { \ - 360, \ - "ORBIT_EXECUTION_STATUS", \ - 6, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_orbit_execution_status_t, time_usec) }, \ - { "radius", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_orbit_execution_status_t, radius) }, \ - { "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_orbit_execution_status_t, frame) }, \ - { "x", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_orbit_execution_status_t, x) }, \ - { "y", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_orbit_execution_status_t, y) }, \ - { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_orbit_execution_status_t, z) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_ORBIT_EXECUTION_STATUS { \ - "ORBIT_EXECUTION_STATUS", \ - 6, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_orbit_execution_status_t, time_usec) }, \ - { "radius", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_orbit_execution_status_t, radius) }, \ - { "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_orbit_execution_status_t, frame) }, \ - { "x", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_orbit_execution_status_t, x) }, \ - { "y", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_orbit_execution_status_t, y) }, \ - { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_orbit_execution_status_t, z) }, \ - } \ -} -#endif - -/** - * @brief Pack a orbit_execution_status message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @param radius [m] Radius of the orbit circle. Positive values orbit clockwise, negative values orbit counter-clockwise. - * @param frame The coordinate system of the fields: x, y, z. - * @param x X coordinate of center point. Coordinate system depends on frame field: local = x position in meters * 1e4, global = latitude in degrees * 1e7. - * @param y Y coordinate of center point. Coordinate system depends on frame field: local = x position in meters * 1e4, global = latitude in degrees * 1e7. - * @param z [m] Altitude of center point. Coordinate system depends on frame field. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_orbit_execution_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint64_t time_usec, float radius, uint8_t frame, int32_t x, int32_t y, float z) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, radius); - _mav_put_int32_t(buf, 12, x); - _mav_put_int32_t(buf, 16, y); - _mav_put_float(buf, 20, z); - _mav_put_uint8_t(buf, 24, frame); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS_LEN); -#else - mavlink_orbit_execution_status_t packet; - packet.time_usec = time_usec; - packet.radius = radius; - packet.x = x; - packet.y = y; - packet.z = z; - packet.frame = frame; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS_MIN_LEN, MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS_LEN, MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS_CRC); -} - -/** - * @brief Pack a orbit_execution_status message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @param radius [m] Radius of the orbit circle. Positive values orbit clockwise, negative values orbit counter-clockwise. - * @param frame The coordinate system of the fields: x, y, z. - * @param x X coordinate of center point. Coordinate system depends on frame field: local = x position in meters * 1e4, global = latitude in degrees * 1e7. - * @param y Y coordinate of center point. Coordinate system depends on frame field: local = x position in meters * 1e4, global = latitude in degrees * 1e7. - * @param z [m] Altitude of center point. Coordinate system depends on frame field. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_orbit_execution_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint64_t time_usec,float radius,uint8_t frame,int32_t x,int32_t y,float z) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, radius); - _mav_put_int32_t(buf, 12, x); - _mav_put_int32_t(buf, 16, y); - _mav_put_float(buf, 20, z); - _mav_put_uint8_t(buf, 24, frame); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS_LEN); -#else - mavlink_orbit_execution_status_t packet; - packet.time_usec = time_usec; - packet.radius = radius; - packet.x = x; - packet.y = y; - packet.z = z; - packet.frame = frame; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS_MIN_LEN, MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS_LEN, MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS_CRC); -} - -/** - * @brief Encode a orbit_execution_status struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param orbit_execution_status C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_orbit_execution_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_orbit_execution_status_t* orbit_execution_status) -{ - return mavlink_msg_orbit_execution_status_pack(system_id, component_id, msg, orbit_execution_status->time_usec, orbit_execution_status->radius, orbit_execution_status->frame, orbit_execution_status->x, orbit_execution_status->y, orbit_execution_status->z); -} - -/** - * @brief Encode a orbit_execution_status struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param orbit_execution_status C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_orbit_execution_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_orbit_execution_status_t* orbit_execution_status) -{ - return mavlink_msg_orbit_execution_status_pack_chan(system_id, component_id, chan, msg, orbit_execution_status->time_usec, orbit_execution_status->radius, orbit_execution_status->frame, orbit_execution_status->x, orbit_execution_status->y, orbit_execution_status->z); -} - -/** - * @brief Send a orbit_execution_status message - * @param chan MAVLink channel to send the message - * - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @param radius [m] Radius of the orbit circle. Positive values orbit clockwise, negative values orbit counter-clockwise. - * @param frame The coordinate system of the fields: x, y, z. - * @param x X coordinate of center point. Coordinate system depends on frame field: local = x position in meters * 1e4, global = latitude in degrees * 1e7. - * @param y Y coordinate of center point. Coordinate system depends on frame field: local = x position in meters * 1e4, global = latitude in degrees * 1e7. - * @param z [m] Altitude of center point. Coordinate system depends on frame field. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_orbit_execution_status_send(mavlink_channel_t chan, uint64_t time_usec, float radius, uint8_t frame, int32_t x, int32_t y, float z) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, radius); - _mav_put_int32_t(buf, 12, x); - _mav_put_int32_t(buf, 16, y); - _mav_put_float(buf, 20, z); - _mav_put_uint8_t(buf, 24, frame); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS, buf, MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS_MIN_LEN, MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS_LEN, MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS_CRC); -#else - mavlink_orbit_execution_status_t packet; - packet.time_usec = time_usec; - packet.radius = radius; - packet.x = x; - packet.y = y; - packet.z = z; - packet.frame = frame; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS, (const char *)&packet, MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS_MIN_LEN, MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS_LEN, MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS_CRC); -#endif -} - -/** - * @brief Send a orbit_execution_status message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_orbit_execution_status_send_struct(mavlink_channel_t chan, const mavlink_orbit_execution_status_t* orbit_execution_status) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_orbit_execution_status_send(chan, orbit_execution_status->time_usec, orbit_execution_status->radius, orbit_execution_status->frame, orbit_execution_status->x, orbit_execution_status->y, orbit_execution_status->z); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS, (const char *)orbit_execution_status, MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS_MIN_LEN, MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS_LEN, MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS_CRC); -#endif -} - -#if MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_orbit_execution_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, float radius, uint8_t frame, int32_t x, int32_t y, float z) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, radius); - _mav_put_int32_t(buf, 12, x); - _mav_put_int32_t(buf, 16, y); - _mav_put_float(buf, 20, z); - _mav_put_uint8_t(buf, 24, frame); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS, buf, MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS_MIN_LEN, MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS_LEN, MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS_CRC); -#else - mavlink_orbit_execution_status_t *packet = (mavlink_orbit_execution_status_t *)msgbuf; - packet->time_usec = time_usec; - packet->radius = radius; - packet->x = x; - packet->y = y; - packet->z = z; - packet->frame = frame; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS, (const char *)packet, MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS_MIN_LEN, MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS_LEN, MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS_CRC); -#endif -} -#endif - -#endif - -// MESSAGE ORBIT_EXECUTION_STATUS UNPACKING - - -/** - * @brief Get field time_usec from orbit_execution_status message - * - * @return [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - */ -static inline uint64_t mavlink_msg_orbit_execution_status_get_time_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field radius from orbit_execution_status message - * - * @return [m] Radius of the orbit circle. Positive values orbit clockwise, negative values orbit counter-clockwise. - */ -static inline float mavlink_msg_orbit_execution_status_get_radius(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field frame from orbit_execution_status message - * - * @return The coordinate system of the fields: x, y, z. - */ -static inline uint8_t mavlink_msg_orbit_execution_status_get_frame(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 24); -} - -/** - * @brief Get field x from orbit_execution_status message - * - * @return X coordinate of center point. Coordinate system depends on frame field: local = x position in meters * 1e4, global = latitude in degrees * 1e7. - */ -static inline int32_t mavlink_msg_orbit_execution_status_get_x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 12); -} - -/** - * @brief Get field y from orbit_execution_status message - * - * @return Y coordinate of center point. Coordinate system depends on frame field: local = x position in meters * 1e4, global = latitude in degrees * 1e7. - */ -static inline int32_t mavlink_msg_orbit_execution_status_get_y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 16); -} - -/** - * @brief Get field z from orbit_execution_status message - * - * @return [m] Altitude of center point. Coordinate system depends on frame field. - */ -static inline float mavlink_msg_orbit_execution_status_get_z(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Decode a orbit_execution_status message into a struct - * - * @param msg The message to decode - * @param orbit_execution_status C-struct to decode the message contents into - */ -static inline void mavlink_msg_orbit_execution_status_decode(const mavlink_message_t* msg, mavlink_orbit_execution_status_t* orbit_execution_status) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - orbit_execution_status->time_usec = mavlink_msg_orbit_execution_status_get_time_usec(msg); - orbit_execution_status->radius = mavlink_msg_orbit_execution_status_get_radius(msg); - orbit_execution_status->x = mavlink_msg_orbit_execution_status_get_x(msg); - orbit_execution_status->y = mavlink_msg_orbit_execution_status_get_y(msg); - orbit_execution_status->z = mavlink_msg_orbit_execution_status_get_z(msg); - orbit_execution_status->frame = mavlink_msg_orbit_execution_status_get_frame(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS_LEN? msg->len : MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS_LEN; - memset(orbit_execution_status, 0, MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS_LEN); - memcpy(orbit_execution_status, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_param_ext_ack.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_param_ext_ack.h deleted file mode 100644 index e3da02b5..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_param_ext_ack.h +++ /dev/null @@ -1,281 +0,0 @@ -#pragma once -// MESSAGE PARAM_EXT_ACK PACKING - -#define MAVLINK_MSG_ID_PARAM_EXT_ACK 324 - - -typedef struct __mavlink_param_ext_ack_t { - char param_id[16]; /*< Parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string*/ - char param_value[128]; /*< Parameter value (new value if PARAM_ACK_ACCEPTED, current value otherwise)*/ - uint8_t param_type; /*< Parameter type.*/ - uint8_t param_result; /*< Result code.*/ -} mavlink_param_ext_ack_t; - -#define MAVLINK_MSG_ID_PARAM_EXT_ACK_LEN 146 -#define MAVLINK_MSG_ID_PARAM_EXT_ACK_MIN_LEN 146 -#define MAVLINK_MSG_ID_324_LEN 146 -#define MAVLINK_MSG_ID_324_MIN_LEN 146 - -#define MAVLINK_MSG_ID_PARAM_EXT_ACK_CRC 132 -#define MAVLINK_MSG_ID_324_CRC 132 - -#define MAVLINK_MSG_PARAM_EXT_ACK_FIELD_PARAM_ID_LEN 16 -#define MAVLINK_MSG_PARAM_EXT_ACK_FIELD_PARAM_VALUE_LEN 128 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_PARAM_EXT_ACK { \ - 324, \ - "PARAM_EXT_ACK", \ - 4, \ - { { "param_id", NULL, MAVLINK_TYPE_CHAR, 16, 0, offsetof(mavlink_param_ext_ack_t, param_id) }, \ - { "param_value", NULL, MAVLINK_TYPE_CHAR, 128, 16, offsetof(mavlink_param_ext_ack_t, param_value) }, \ - { "param_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 144, offsetof(mavlink_param_ext_ack_t, param_type) }, \ - { "param_result", NULL, MAVLINK_TYPE_UINT8_T, 0, 145, offsetof(mavlink_param_ext_ack_t, param_result) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_PARAM_EXT_ACK { \ - "PARAM_EXT_ACK", \ - 4, \ - { { "param_id", NULL, MAVLINK_TYPE_CHAR, 16, 0, offsetof(mavlink_param_ext_ack_t, param_id) }, \ - { "param_value", NULL, MAVLINK_TYPE_CHAR, 128, 16, offsetof(mavlink_param_ext_ack_t, param_value) }, \ - { "param_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 144, offsetof(mavlink_param_ext_ack_t, param_type) }, \ - { "param_result", NULL, MAVLINK_TYPE_UINT8_T, 0, 145, offsetof(mavlink_param_ext_ack_t, param_result) }, \ - } \ -} -#endif - -/** - * @brief Pack a param_ext_ack message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param param_id Parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string - * @param param_value Parameter value (new value if PARAM_ACK_ACCEPTED, current value otherwise) - * @param param_type Parameter type. - * @param param_result Result code. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_param_ext_ack_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - const char *param_id, const char *param_value, uint8_t param_type, uint8_t param_result) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_PARAM_EXT_ACK_LEN]; - _mav_put_uint8_t(buf, 144, param_type); - _mav_put_uint8_t(buf, 145, param_result); - _mav_put_char_array(buf, 0, param_id, 16); - _mav_put_char_array(buf, 16, param_value, 128); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PARAM_EXT_ACK_LEN); -#else - mavlink_param_ext_ack_t packet; - packet.param_type = param_type; - packet.param_result = param_result; - mav_array_memcpy(packet.param_id, param_id, sizeof(char)*16); - mav_array_memcpy(packet.param_value, param_value, sizeof(char)*128); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PARAM_EXT_ACK_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_PARAM_EXT_ACK; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PARAM_EXT_ACK_MIN_LEN, MAVLINK_MSG_ID_PARAM_EXT_ACK_LEN, MAVLINK_MSG_ID_PARAM_EXT_ACK_CRC); -} - -/** - * @brief Pack a param_ext_ack message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param param_id Parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string - * @param param_value Parameter value (new value if PARAM_ACK_ACCEPTED, current value otherwise) - * @param param_type Parameter type. - * @param param_result Result code. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_param_ext_ack_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - const char *param_id,const char *param_value,uint8_t param_type,uint8_t param_result) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_PARAM_EXT_ACK_LEN]; - _mav_put_uint8_t(buf, 144, param_type); - _mav_put_uint8_t(buf, 145, param_result); - _mav_put_char_array(buf, 0, param_id, 16); - _mav_put_char_array(buf, 16, param_value, 128); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PARAM_EXT_ACK_LEN); -#else - mavlink_param_ext_ack_t packet; - packet.param_type = param_type; - packet.param_result = param_result; - mav_array_memcpy(packet.param_id, param_id, sizeof(char)*16); - mav_array_memcpy(packet.param_value, param_value, sizeof(char)*128); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PARAM_EXT_ACK_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_PARAM_EXT_ACK; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_PARAM_EXT_ACK_MIN_LEN, MAVLINK_MSG_ID_PARAM_EXT_ACK_LEN, MAVLINK_MSG_ID_PARAM_EXT_ACK_CRC); -} - -/** - * @brief Encode a param_ext_ack struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param param_ext_ack C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_param_ext_ack_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_param_ext_ack_t* param_ext_ack) -{ - return mavlink_msg_param_ext_ack_pack(system_id, component_id, msg, param_ext_ack->param_id, param_ext_ack->param_value, param_ext_ack->param_type, param_ext_ack->param_result); -} - -/** - * @brief Encode a param_ext_ack struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param param_ext_ack C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_param_ext_ack_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_param_ext_ack_t* param_ext_ack) -{ - return mavlink_msg_param_ext_ack_pack_chan(system_id, component_id, chan, msg, param_ext_ack->param_id, param_ext_ack->param_value, param_ext_ack->param_type, param_ext_ack->param_result); -} - -/** - * @brief Send a param_ext_ack message - * @param chan MAVLink channel to send the message - * - * @param param_id Parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string - * @param param_value Parameter value (new value if PARAM_ACK_ACCEPTED, current value otherwise) - * @param param_type Parameter type. - * @param param_result Result code. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_param_ext_ack_send(mavlink_channel_t chan, const char *param_id, const char *param_value, uint8_t param_type, uint8_t param_result) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_PARAM_EXT_ACK_LEN]; - _mav_put_uint8_t(buf, 144, param_type); - _mav_put_uint8_t(buf, 145, param_result); - _mav_put_char_array(buf, 0, param_id, 16); - _mav_put_char_array(buf, 16, param_value, 128); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_EXT_ACK, buf, MAVLINK_MSG_ID_PARAM_EXT_ACK_MIN_LEN, MAVLINK_MSG_ID_PARAM_EXT_ACK_LEN, MAVLINK_MSG_ID_PARAM_EXT_ACK_CRC); -#else - mavlink_param_ext_ack_t packet; - packet.param_type = param_type; - packet.param_result = param_result; - mav_array_memcpy(packet.param_id, param_id, sizeof(char)*16); - mav_array_memcpy(packet.param_value, param_value, sizeof(char)*128); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_EXT_ACK, (const char *)&packet, MAVLINK_MSG_ID_PARAM_EXT_ACK_MIN_LEN, MAVLINK_MSG_ID_PARAM_EXT_ACK_LEN, MAVLINK_MSG_ID_PARAM_EXT_ACK_CRC); -#endif -} - -/** - * @brief Send a param_ext_ack message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_param_ext_ack_send_struct(mavlink_channel_t chan, const mavlink_param_ext_ack_t* param_ext_ack) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_param_ext_ack_send(chan, param_ext_ack->param_id, param_ext_ack->param_value, param_ext_ack->param_type, param_ext_ack->param_result); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_EXT_ACK, (const char *)param_ext_ack, MAVLINK_MSG_ID_PARAM_EXT_ACK_MIN_LEN, MAVLINK_MSG_ID_PARAM_EXT_ACK_LEN, MAVLINK_MSG_ID_PARAM_EXT_ACK_CRC); -#endif -} - -#if MAVLINK_MSG_ID_PARAM_EXT_ACK_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_param_ext_ack_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, const char *param_id, const char *param_value, uint8_t param_type, uint8_t param_result) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint8_t(buf, 144, param_type); - _mav_put_uint8_t(buf, 145, param_result); - _mav_put_char_array(buf, 0, param_id, 16); - _mav_put_char_array(buf, 16, param_value, 128); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_EXT_ACK, buf, MAVLINK_MSG_ID_PARAM_EXT_ACK_MIN_LEN, MAVLINK_MSG_ID_PARAM_EXT_ACK_LEN, MAVLINK_MSG_ID_PARAM_EXT_ACK_CRC); -#else - mavlink_param_ext_ack_t *packet = (mavlink_param_ext_ack_t *)msgbuf; - packet->param_type = param_type; - packet->param_result = param_result; - mav_array_memcpy(packet->param_id, param_id, sizeof(char)*16); - mav_array_memcpy(packet->param_value, param_value, sizeof(char)*128); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_EXT_ACK, (const char *)packet, MAVLINK_MSG_ID_PARAM_EXT_ACK_MIN_LEN, MAVLINK_MSG_ID_PARAM_EXT_ACK_LEN, MAVLINK_MSG_ID_PARAM_EXT_ACK_CRC); -#endif -} -#endif - -#endif - -// MESSAGE PARAM_EXT_ACK UNPACKING - - -/** - * @brief Get field param_id from param_ext_ack message - * - * @return Parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string - */ -static inline uint16_t mavlink_msg_param_ext_ack_get_param_id(const mavlink_message_t* msg, char *param_id) -{ - return _MAV_RETURN_char_array(msg, param_id, 16, 0); -} - -/** - * @brief Get field param_value from param_ext_ack message - * - * @return Parameter value (new value if PARAM_ACK_ACCEPTED, current value otherwise) - */ -static inline uint16_t mavlink_msg_param_ext_ack_get_param_value(const mavlink_message_t* msg, char *param_value) -{ - return _MAV_RETURN_char_array(msg, param_value, 128, 16); -} - -/** - * @brief Get field param_type from param_ext_ack message - * - * @return Parameter type. - */ -static inline uint8_t mavlink_msg_param_ext_ack_get_param_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 144); -} - -/** - * @brief Get field param_result from param_ext_ack message - * - * @return Result code. - */ -static inline uint8_t mavlink_msg_param_ext_ack_get_param_result(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 145); -} - -/** - * @brief Decode a param_ext_ack message into a struct - * - * @param msg The message to decode - * @param param_ext_ack C-struct to decode the message contents into - */ -static inline void mavlink_msg_param_ext_ack_decode(const mavlink_message_t* msg, mavlink_param_ext_ack_t* param_ext_ack) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_param_ext_ack_get_param_id(msg, param_ext_ack->param_id); - mavlink_msg_param_ext_ack_get_param_value(msg, param_ext_ack->param_value); - param_ext_ack->param_type = mavlink_msg_param_ext_ack_get_param_type(msg); - param_ext_ack->param_result = mavlink_msg_param_ext_ack_get_param_result(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_PARAM_EXT_ACK_LEN? msg->len : MAVLINK_MSG_ID_PARAM_EXT_ACK_LEN; - memset(param_ext_ack, 0, MAVLINK_MSG_ID_PARAM_EXT_ACK_LEN); - memcpy(param_ext_ack, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_param_ext_request_list.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_param_ext_request_list.h deleted file mode 100644 index 945fd0c3..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_param_ext_request_list.h +++ /dev/null @@ -1,238 +0,0 @@ -#pragma once -// MESSAGE PARAM_EXT_REQUEST_LIST PACKING - -#define MAVLINK_MSG_ID_PARAM_EXT_REQUEST_LIST 321 - - -typedef struct __mavlink_param_ext_request_list_t { - uint8_t target_system; /*< System ID*/ - uint8_t target_component; /*< Component ID*/ -} mavlink_param_ext_request_list_t; - -#define MAVLINK_MSG_ID_PARAM_EXT_REQUEST_LIST_LEN 2 -#define MAVLINK_MSG_ID_PARAM_EXT_REQUEST_LIST_MIN_LEN 2 -#define MAVLINK_MSG_ID_321_LEN 2 -#define MAVLINK_MSG_ID_321_MIN_LEN 2 - -#define MAVLINK_MSG_ID_PARAM_EXT_REQUEST_LIST_CRC 88 -#define MAVLINK_MSG_ID_321_CRC 88 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_PARAM_EXT_REQUEST_LIST { \ - 321, \ - "PARAM_EXT_REQUEST_LIST", \ - 2, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_param_ext_request_list_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_param_ext_request_list_t, target_component) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_PARAM_EXT_REQUEST_LIST { \ - "PARAM_EXT_REQUEST_LIST", \ - 2, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_param_ext_request_list_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_param_ext_request_list_t, target_component) }, \ - } \ -} -#endif - -/** - * @brief Pack a param_ext_request_list message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID - * @param target_component Component ID - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_param_ext_request_list_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_PARAM_EXT_REQUEST_LIST_LEN]; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PARAM_EXT_REQUEST_LIST_LEN); -#else - mavlink_param_ext_request_list_t packet; - packet.target_system = target_system; - packet.target_component = target_component; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PARAM_EXT_REQUEST_LIST_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_PARAM_EXT_REQUEST_LIST; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PARAM_EXT_REQUEST_LIST_MIN_LEN, MAVLINK_MSG_ID_PARAM_EXT_REQUEST_LIST_LEN, MAVLINK_MSG_ID_PARAM_EXT_REQUEST_LIST_CRC); -} - -/** - * @brief Pack a param_ext_request_list message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_param_ext_request_list_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_PARAM_EXT_REQUEST_LIST_LEN]; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PARAM_EXT_REQUEST_LIST_LEN); -#else - mavlink_param_ext_request_list_t packet; - packet.target_system = target_system; - packet.target_component = target_component; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PARAM_EXT_REQUEST_LIST_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_PARAM_EXT_REQUEST_LIST; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_PARAM_EXT_REQUEST_LIST_MIN_LEN, MAVLINK_MSG_ID_PARAM_EXT_REQUEST_LIST_LEN, MAVLINK_MSG_ID_PARAM_EXT_REQUEST_LIST_CRC); -} - -/** - * @brief Encode a param_ext_request_list struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param param_ext_request_list C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_param_ext_request_list_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_param_ext_request_list_t* param_ext_request_list) -{ - return mavlink_msg_param_ext_request_list_pack(system_id, component_id, msg, param_ext_request_list->target_system, param_ext_request_list->target_component); -} - -/** - * @brief Encode a param_ext_request_list struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param param_ext_request_list C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_param_ext_request_list_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_param_ext_request_list_t* param_ext_request_list) -{ - return mavlink_msg_param_ext_request_list_pack_chan(system_id, component_id, chan, msg, param_ext_request_list->target_system, param_ext_request_list->target_component); -} - -/** - * @brief Send a param_ext_request_list message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param target_component Component ID - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_param_ext_request_list_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_PARAM_EXT_REQUEST_LIST_LEN]; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_EXT_REQUEST_LIST, buf, MAVLINK_MSG_ID_PARAM_EXT_REQUEST_LIST_MIN_LEN, MAVLINK_MSG_ID_PARAM_EXT_REQUEST_LIST_LEN, MAVLINK_MSG_ID_PARAM_EXT_REQUEST_LIST_CRC); -#else - mavlink_param_ext_request_list_t packet; - packet.target_system = target_system; - packet.target_component = target_component; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_EXT_REQUEST_LIST, (const char *)&packet, MAVLINK_MSG_ID_PARAM_EXT_REQUEST_LIST_MIN_LEN, MAVLINK_MSG_ID_PARAM_EXT_REQUEST_LIST_LEN, MAVLINK_MSG_ID_PARAM_EXT_REQUEST_LIST_CRC); -#endif -} - -/** - * @brief Send a param_ext_request_list message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_param_ext_request_list_send_struct(mavlink_channel_t chan, const mavlink_param_ext_request_list_t* param_ext_request_list) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_param_ext_request_list_send(chan, param_ext_request_list->target_system, param_ext_request_list->target_component); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_EXT_REQUEST_LIST, (const char *)param_ext_request_list, MAVLINK_MSG_ID_PARAM_EXT_REQUEST_LIST_MIN_LEN, MAVLINK_MSG_ID_PARAM_EXT_REQUEST_LIST_LEN, MAVLINK_MSG_ID_PARAM_EXT_REQUEST_LIST_CRC); -#endif -} - -#if MAVLINK_MSG_ID_PARAM_EXT_REQUEST_LIST_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_param_ext_request_list_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_EXT_REQUEST_LIST, buf, MAVLINK_MSG_ID_PARAM_EXT_REQUEST_LIST_MIN_LEN, MAVLINK_MSG_ID_PARAM_EXT_REQUEST_LIST_LEN, MAVLINK_MSG_ID_PARAM_EXT_REQUEST_LIST_CRC); -#else - mavlink_param_ext_request_list_t *packet = (mavlink_param_ext_request_list_t *)msgbuf; - packet->target_system = target_system; - packet->target_component = target_component; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_EXT_REQUEST_LIST, (const char *)packet, MAVLINK_MSG_ID_PARAM_EXT_REQUEST_LIST_MIN_LEN, MAVLINK_MSG_ID_PARAM_EXT_REQUEST_LIST_LEN, MAVLINK_MSG_ID_PARAM_EXT_REQUEST_LIST_CRC); -#endif -} -#endif - -#endif - -// MESSAGE PARAM_EXT_REQUEST_LIST UNPACKING - - -/** - * @brief Get field target_system from param_ext_request_list message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_param_ext_request_list_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 0); -} - -/** - * @brief Get field target_component from param_ext_request_list message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_param_ext_request_list_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 1); -} - -/** - * @brief Decode a param_ext_request_list message into a struct - * - * @param msg The message to decode - * @param param_ext_request_list C-struct to decode the message contents into - */ -static inline void mavlink_msg_param_ext_request_list_decode(const mavlink_message_t* msg, mavlink_param_ext_request_list_t* param_ext_request_list) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - param_ext_request_list->target_system = mavlink_msg_param_ext_request_list_get_target_system(msg); - param_ext_request_list->target_component = mavlink_msg_param_ext_request_list_get_target_component(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_PARAM_EXT_REQUEST_LIST_LEN? msg->len : MAVLINK_MSG_ID_PARAM_EXT_REQUEST_LIST_LEN; - memset(param_ext_request_list, 0, MAVLINK_MSG_ID_PARAM_EXT_REQUEST_LIST_LEN); - memcpy(param_ext_request_list, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_param_ext_request_read.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_param_ext_request_read.h deleted file mode 100644 index 3c18f63d..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_param_ext_request_read.h +++ /dev/null @@ -1,280 +0,0 @@ -#pragma once -// MESSAGE PARAM_EXT_REQUEST_READ PACKING - -#define MAVLINK_MSG_ID_PARAM_EXT_REQUEST_READ 320 - - -typedef struct __mavlink_param_ext_request_read_t { - int16_t param_index; /*< Parameter index. Set to -1 to use the Parameter ID field as identifier (else param_id will be ignored)*/ - uint8_t target_system; /*< System ID*/ - uint8_t target_component; /*< Component ID*/ - char param_id[16]; /*< Parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string*/ -} mavlink_param_ext_request_read_t; - -#define MAVLINK_MSG_ID_PARAM_EXT_REQUEST_READ_LEN 20 -#define MAVLINK_MSG_ID_PARAM_EXT_REQUEST_READ_MIN_LEN 20 -#define MAVLINK_MSG_ID_320_LEN 20 -#define MAVLINK_MSG_ID_320_MIN_LEN 20 - -#define MAVLINK_MSG_ID_PARAM_EXT_REQUEST_READ_CRC 243 -#define MAVLINK_MSG_ID_320_CRC 243 - -#define MAVLINK_MSG_PARAM_EXT_REQUEST_READ_FIELD_PARAM_ID_LEN 16 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_PARAM_EXT_REQUEST_READ { \ - 320, \ - "PARAM_EXT_REQUEST_READ", \ - 4, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_param_ext_request_read_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_param_ext_request_read_t, target_component) }, \ - { "param_id", NULL, MAVLINK_TYPE_CHAR, 16, 4, offsetof(mavlink_param_ext_request_read_t, param_id) }, \ - { "param_index", NULL, MAVLINK_TYPE_INT16_T, 0, 0, offsetof(mavlink_param_ext_request_read_t, param_index) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_PARAM_EXT_REQUEST_READ { \ - "PARAM_EXT_REQUEST_READ", \ - 4, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_param_ext_request_read_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_param_ext_request_read_t, target_component) }, \ - { "param_id", NULL, MAVLINK_TYPE_CHAR, 16, 4, offsetof(mavlink_param_ext_request_read_t, param_id) }, \ - { "param_index", NULL, MAVLINK_TYPE_INT16_T, 0, 0, offsetof(mavlink_param_ext_request_read_t, param_index) }, \ - } \ -} -#endif - -/** - * @brief Pack a param_ext_request_read message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID - * @param target_component Component ID - * @param param_id Parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string - * @param param_index Parameter index. Set to -1 to use the Parameter ID field as identifier (else param_id will be ignored) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_param_ext_request_read_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component, const char *param_id, int16_t param_index) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_PARAM_EXT_REQUEST_READ_LEN]; - _mav_put_int16_t(buf, 0, param_index); - _mav_put_uint8_t(buf, 2, target_system); - _mav_put_uint8_t(buf, 3, target_component); - _mav_put_char_array(buf, 4, param_id, 16); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PARAM_EXT_REQUEST_READ_LEN); -#else - mavlink_param_ext_request_read_t packet; - packet.param_index = param_index; - packet.target_system = target_system; - packet.target_component = target_component; - mav_array_memcpy(packet.param_id, param_id, sizeof(char)*16); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PARAM_EXT_REQUEST_READ_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_PARAM_EXT_REQUEST_READ; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PARAM_EXT_REQUEST_READ_MIN_LEN, MAVLINK_MSG_ID_PARAM_EXT_REQUEST_READ_LEN, MAVLINK_MSG_ID_PARAM_EXT_REQUEST_READ_CRC); -} - -/** - * @brief Pack a param_ext_request_read message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @param param_id Parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string - * @param param_index Parameter index. Set to -1 to use the Parameter ID field as identifier (else param_id will be ignored) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_param_ext_request_read_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component,const char *param_id,int16_t param_index) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_PARAM_EXT_REQUEST_READ_LEN]; - _mav_put_int16_t(buf, 0, param_index); - _mav_put_uint8_t(buf, 2, target_system); - _mav_put_uint8_t(buf, 3, target_component); - _mav_put_char_array(buf, 4, param_id, 16); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PARAM_EXT_REQUEST_READ_LEN); -#else - mavlink_param_ext_request_read_t packet; - packet.param_index = param_index; - packet.target_system = target_system; - packet.target_component = target_component; - mav_array_memcpy(packet.param_id, param_id, sizeof(char)*16); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PARAM_EXT_REQUEST_READ_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_PARAM_EXT_REQUEST_READ; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_PARAM_EXT_REQUEST_READ_MIN_LEN, MAVLINK_MSG_ID_PARAM_EXT_REQUEST_READ_LEN, MAVLINK_MSG_ID_PARAM_EXT_REQUEST_READ_CRC); -} - -/** - * @brief Encode a param_ext_request_read struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param param_ext_request_read C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_param_ext_request_read_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_param_ext_request_read_t* param_ext_request_read) -{ - return mavlink_msg_param_ext_request_read_pack(system_id, component_id, msg, param_ext_request_read->target_system, param_ext_request_read->target_component, param_ext_request_read->param_id, param_ext_request_read->param_index); -} - -/** - * @brief Encode a param_ext_request_read struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param param_ext_request_read C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_param_ext_request_read_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_param_ext_request_read_t* param_ext_request_read) -{ - return mavlink_msg_param_ext_request_read_pack_chan(system_id, component_id, chan, msg, param_ext_request_read->target_system, param_ext_request_read->target_component, param_ext_request_read->param_id, param_ext_request_read->param_index); -} - -/** - * @brief Send a param_ext_request_read message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param target_component Component ID - * @param param_id Parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string - * @param param_index Parameter index. Set to -1 to use the Parameter ID field as identifier (else param_id will be ignored) - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_param_ext_request_read_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, const char *param_id, int16_t param_index) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_PARAM_EXT_REQUEST_READ_LEN]; - _mav_put_int16_t(buf, 0, param_index); - _mav_put_uint8_t(buf, 2, target_system); - _mav_put_uint8_t(buf, 3, target_component); - _mav_put_char_array(buf, 4, param_id, 16); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_EXT_REQUEST_READ, buf, MAVLINK_MSG_ID_PARAM_EXT_REQUEST_READ_MIN_LEN, MAVLINK_MSG_ID_PARAM_EXT_REQUEST_READ_LEN, MAVLINK_MSG_ID_PARAM_EXT_REQUEST_READ_CRC); -#else - mavlink_param_ext_request_read_t packet; - packet.param_index = param_index; - packet.target_system = target_system; - packet.target_component = target_component; - mav_array_memcpy(packet.param_id, param_id, sizeof(char)*16); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_EXT_REQUEST_READ, (const char *)&packet, MAVLINK_MSG_ID_PARAM_EXT_REQUEST_READ_MIN_LEN, MAVLINK_MSG_ID_PARAM_EXT_REQUEST_READ_LEN, MAVLINK_MSG_ID_PARAM_EXT_REQUEST_READ_CRC); -#endif -} - -/** - * @brief Send a param_ext_request_read message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_param_ext_request_read_send_struct(mavlink_channel_t chan, const mavlink_param_ext_request_read_t* param_ext_request_read) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_param_ext_request_read_send(chan, param_ext_request_read->target_system, param_ext_request_read->target_component, param_ext_request_read->param_id, param_ext_request_read->param_index); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_EXT_REQUEST_READ, (const char *)param_ext_request_read, MAVLINK_MSG_ID_PARAM_EXT_REQUEST_READ_MIN_LEN, MAVLINK_MSG_ID_PARAM_EXT_REQUEST_READ_LEN, MAVLINK_MSG_ID_PARAM_EXT_REQUEST_READ_CRC); -#endif -} - -#if MAVLINK_MSG_ID_PARAM_EXT_REQUEST_READ_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_param_ext_request_read_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, const char *param_id, int16_t param_index) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_int16_t(buf, 0, param_index); - _mav_put_uint8_t(buf, 2, target_system); - _mav_put_uint8_t(buf, 3, target_component); - _mav_put_char_array(buf, 4, param_id, 16); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_EXT_REQUEST_READ, buf, MAVLINK_MSG_ID_PARAM_EXT_REQUEST_READ_MIN_LEN, MAVLINK_MSG_ID_PARAM_EXT_REQUEST_READ_LEN, MAVLINK_MSG_ID_PARAM_EXT_REQUEST_READ_CRC); -#else - mavlink_param_ext_request_read_t *packet = (mavlink_param_ext_request_read_t *)msgbuf; - packet->param_index = param_index; - packet->target_system = target_system; - packet->target_component = target_component; - mav_array_memcpy(packet->param_id, param_id, sizeof(char)*16); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_EXT_REQUEST_READ, (const char *)packet, MAVLINK_MSG_ID_PARAM_EXT_REQUEST_READ_MIN_LEN, MAVLINK_MSG_ID_PARAM_EXT_REQUEST_READ_LEN, MAVLINK_MSG_ID_PARAM_EXT_REQUEST_READ_CRC); -#endif -} -#endif - -#endif - -// MESSAGE PARAM_EXT_REQUEST_READ UNPACKING - - -/** - * @brief Get field target_system from param_ext_request_read message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_param_ext_request_read_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 2); -} - -/** - * @brief Get field target_component from param_ext_request_read message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_param_ext_request_read_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 3); -} - -/** - * @brief Get field param_id from param_ext_request_read message - * - * @return Parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string - */ -static inline uint16_t mavlink_msg_param_ext_request_read_get_param_id(const mavlink_message_t* msg, char *param_id) -{ - return _MAV_RETURN_char_array(msg, param_id, 16, 4); -} - -/** - * @brief Get field param_index from param_ext_request_read message - * - * @return Parameter index. Set to -1 to use the Parameter ID field as identifier (else param_id will be ignored) - */ -static inline int16_t mavlink_msg_param_ext_request_read_get_param_index(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 0); -} - -/** - * @brief Decode a param_ext_request_read message into a struct - * - * @param msg The message to decode - * @param param_ext_request_read C-struct to decode the message contents into - */ -static inline void mavlink_msg_param_ext_request_read_decode(const mavlink_message_t* msg, mavlink_param_ext_request_read_t* param_ext_request_read) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - param_ext_request_read->param_index = mavlink_msg_param_ext_request_read_get_param_index(msg); - param_ext_request_read->target_system = mavlink_msg_param_ext_request_read_get_target_system(msg); - param_ext_request_read->target_component = mavlink_msg_param_ext_request_read_get_target_component(msg); - mavlink_msg_param_ext_request_read_get_param_id(msg, param_ext_request_read->param_id); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_PARAM_EXT_REQUEST_READ_LEN? msg->len : MAVLINK_MSG_ID_PARAM_EXT_REQUEST_READ_LEN; - memset(param_ext_request_read, 0, MAVLINK_MSG_ID_PARAM_EXT_REQUEST_READ_LEN); - memcpy(param_ext_request_read, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_param_ext_set.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_param_ext_set.h deleted file mode 100644 index c17e0a32..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_param_ext_set.h +++ /dev/null @@ -1,306 +0,0 @@ -#pragma once -// MESSAGE PARAM_EXT_SET PACKING - -#define MAVLINK_MSG_ID_PARAM_EXT_SET 323 - - -typedef struct __mavlink_param_ext_set_t { - uint8_t target_system; /*< System ID*/ - uint8_t target_component; /*< Component ID*/ - char param_id[16]; /*< Parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string*/ - char param_value[128]; /*< Parameter value*/ - uint8_t param_type; /*< Parameter type.*/ -} mavlink_param_ext_set_t; - -#define MAVLINK_MSG_ID_PARAM_EXT_SET_LEN 147 -#define MAVLINK_MSG_ID_PARAM_EXT_SET_MIN_LEN 147 -#define MAVLINK_MSG_ID_323_LEN 147 -#define MAVLINK_MSG_ID_323_MIN_LEN 147 - -#define MAVLINK_MSG_ID_PARAM_EXT_SET_CRC 78 -#define MAVLINK_MSG_ID_323_CRC 78 - -#define MAVLINK_MSG_PARAM_EXT_SET_FIELD_PARAM_ID_LEN 16 -#define MAVLINK_MSG_PARAM_EXT_SET_FIELD_PARAM_VALUE_LEN 128 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_PARAM_EXT_SET { \ - 323, \ - "PARAM_EXT_SET", \ - 5, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_param_ext_set_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_param_ext_set_t, target_component) }, \ - { "param_id", NULL, MAVLINK_TYPE_CHAR, 16, 2, offsetof(mavlink_param_ext_set_t, param_id) }, \ - { "param_value", NULL, MAVLINK_TYPE_CHAR, 128, 18, offsetof(mavlink_param_ext_set_t, param_value) }, \ - { "param_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 146, offsetof(mavlink_param_ext_set_t, param_type) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_PARAM_EXT_SET { \ - "PARAM_EXT_SET", \ - 5, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_param_ext_set_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_param_ext_set_t, target_component) }, \ - { "param_id", NULL, MAVLINK_TYPE_CHAR, 16, 2, offsetof(mavlink_param_ext_set_t, param_id) }, \ - { "param_value", NULL, MAVLINK_TYPE_CHAR, 128, 18, offsetof(mavlink_param_ext_set_t, param_value) }, \ - { "param_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 146, offsetof(mavlink_param_ext_set_t, param_type) }, \ - } \ -} -#endif - -/** - * @brief Pack a param_ext_set message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID - * @param target_component Component ID - * @param param_id Parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string - * @param param_value Parameter value - * @param param_type Parameter type. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_param_ext_set_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component, const char *param_id, const char *param_value, uint8_t param_type) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_PARAM_EXT_SET_LEN]; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - _mav_put_uint8_t(buf, 146, param_type); - _mav_put_char_array(buf, 2, param_id, 16); - _mav_put_char_array(buf, 18, param_value, 128); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PARAM_EXT_SET_LEN); -#else - mavlink_param_ext_set_t packet; - packet.target_system = target_system; - packet.target_component = target_component; - packet.param_type = param_type; - mav_array_memcpy(packet.param_id, param_id, sizeof(char)*16); - mav_array_memcpy(packet.param_value, param_value, sizeof(char)*128); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PARAM_EXT_SET_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_PARAM_EXT_SET; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PARAM_EXT_SET_MIN_LEN, MAVLINK_MSG_ID_PARAM_EXT_SET_LEN, MAVLINK_MSG_ID_PARAM_EXT_SET_CRC); -} - -/** - * @brief Pack a param_ext_set message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @param param_id Parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string - * @param param_value Parameter value - * @param param_type Parameter type. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_param_ext_set_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component,const char *param_id,const char *param_value,uint8_t param_type) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_PARAM_EXT_SET_LEN]; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - _mav_put_uint8_t(buf, 146, param_type); - _mav_put_char_array(buf, 2, param_id, 16); - _mav_put_char_array(buf, 18, param_value, 128); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PARAM_EXT_SET_LEN); -#else - mavlink_param_ext_set_t packet; - packet.target_system = target_system; - packet.target_component = target_component; - packet.param_type = param_type; - mav_array_memcpy(packet.param_id, param_id, sizeof(char)*16); - mav_array_memcpy(packet.param_value, param_value, sizeof(char)*128); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PARAM_EXT_SET_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_PARAM_EXT_SET; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_PARAM_EXT_SET_MIN_LEN, MAVLINK_MSG_ID_PARAM_EXT_SET_LEN, MAVLINK_MSG_ID_PARAM_EXT_SET_CRC); -} - -/** - * @brief Encode a param_ext_set struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param param_ext_set C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_param_ext_set_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_param_ext_set_t* param_ext_set) -{ - return mavlink_msg_param_ext_set_pack(system_id, component_id, msg, param_ext_set->target_system, param_ext_set->target_component, param_ext_set->param_id, param_ext_set->param_value, param_ext_set->param_type); -} - -/** - * @brief Encode a param_ext_set struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param param_ext_set C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_param_ext_set_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_param_ext_set_t* param_ext_set) -{ - return mavlink_msg_param_ext_set_pack_chan(system_id, component_id, chan, msg, param_ext_set->target_system, param_ext_set->target_component, param_ext_set->param_id, param_ext_set->param_value, param_ext_set->param_type); -} - -/** - * @brief Send a param_ext_set message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param target_component Component ID - * @param param_id Parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string - * @param param_value Parameter value - * @param param_type Parameter type. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_param_ext_set_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, const char *param_id, const char *param_value, uint8_t param_type) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_PARAM_EXT_SET_LEN]; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - _mav_put_uint8_t(buf, 146, param_type); - _mav_put_char_array(buf, 2, param_id, 16); - _mav_put_char_array(buf, 18, param_value, 128); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_EXT_SET, buf, MAVLINK_MSG_ID_PARAM_EXT_SET_MIN_LEN, MAVLINK_MSG_ID_PARAM_EXT_SET_LEN, MAVLINK_MSG_ID_PARAM_EXT_SET_CRC); -#else - mavlink_param_ext_set_t packet; - packet.target_system = target_system; - packet.target_component = target_component; - packet.param_type = param_type; - mav_array_memcpy(packet.param_id, param_id, sizeof(char)*16); - mav_array_memcpy(packet.param_value, param_value, sizeof(char)*128); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_EXT_SET, (const char *)&packet, MAVLINK_MSG_ID_PARAM_EXT_SET_MIN_LEN, MAVLINK_MSG_ID_PARAM_EXT_SET_LEN, MAVLINK_MSG_ID_PARAM_EXT_SET_CRC); -#endif -} - -/** - * @brief Send a param_ext_set message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_param_ext_set_send_struct(mavlink_channel_t chan, const mavlink_param_ext_set_t* param_ext_set) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_param_ext_set_send(chan, param_ext_set->target_system, param_ext_set->target_component, param_ext_set->param_id, param_ext_set->param_value, param_ext_set->param_type); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_EXT_SET, (const char *)param_ext_set, MAVLINK_MSG_ID_PARAM_EXT_SET_MIN_LEN, MAVLINK_MSG_ID_PARAM_EXT_SET_LEN, MAVLINK_MSG_ID_PARAM_EXT_SET_CRC); -#endif -} - -#if MAVLINK_MSG_ID_PARAM_EXT_SET_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_param_ext_set_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, const char *param_id, const char *param_value, uint8_t param_type) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - _mav_put_uint8_t(buf, 146, param_type); - _mav_put_char_array(buf, 2, param_id, 16); - _mav_put_char_array(buf, 18, param_value, 128); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_EXT_SET, buf, MAVLINK_MSG_ID_PARAM_EXT_SET_MIN_LEN, MAVLINK_MSG_ID_PARAM_EXT_SET_LEN, MAVLINK_MSG_ID_PARAM_EXT_SET_CRC); -#else - mavlink_param_ext_set_t *packet = (mavlink_param_ext_set_t *)msgbuf; - packet->target_system = target_system; - packet->target_component = target_component; - packet->param_type = param_type; - mav_array_memcpy(packet->param_id, param_id, sizeof(char)*16); - mav_array_memcpy(packet->param_value, param_value, sizeof(char)*128); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_EXT_SET, (const char *)packet, MAVLINK_MSG_ID_PARAM_EXT_SET_MIN_LEN, MAVLINK_MSG_ID_PARAM_EXT_SET_LEN, MAVLINK_MSG_ID_PARAM_EXT_SET_CRC); -#endif -} -#endif - -#endif - -// MESSAGE PARAM_EXT_SET UNPACKING - - -/** - * @brief Get field target_system from param_ext_set message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_param_ext_set_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 0); -} - -/** - * @brief Get field target_component from param_ext_set message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_param_ext_set_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 1); -} - -/** - * @brief Get field param_id from param_ext_set message - * - * @return Parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string - */ -static inline uint16_t mavlink_msg_param_ext_set_get_param_id(const mavlink_message_t* msg, char *param_id) -{ - return _MAV_RETURN_char_array(msg, param_id, 16, 2); -} - -/** - * @brief Get field param_value from param_ext_set message - * - * @return Parameter value - */ -static inline uint16_t mavlink_msg_param_ext_set_get_param_value(const mavlink_message_t* msg, char *param_value) -{ - return _MAV_RETURN_char_array(msg, param_value, 128, 18); -} - -/** - * @brief Get field param_type from param_ext_set message - * - * @return Parameter type. - */ -static inline uint8_t mavlink_msg_param_ext_set_get_param_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 146); -} - -/** - * @brief Decode a param_ext_set message into a struct - * - * @param msg The message to decode - * @param param_ext_set C-struct to decode the message contents into - */ -static inline void mavlink_msg_param_ext_set_decode(const mavlink_message_t* msg, mavlink_param_ext_set_t* param_ext_set) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - param_ext_set->target_system = mavlink_msg_param_ext_set_get_target_system(msg); - param_ext_set->target_component = mavlink_msg_param_ext_set_get_target_component(msg); - mavlink_msg_param_ext_set_get_param_id(msg, param_ext_set->param_id); - mavlink_msg_param_ext_set_get_param_value(msg, param_ext_set->param_value); - param_ext_set->param_type = mavlink_msg_param_ext_set_get_param_type(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_PARAM_EXT_SET_LEN? msg->len : MAVLINK_MSG_ID_PARAM_EXT_SET_LEN; - memset(param_ext_set, 0, MAVLINK_MSG_ID_PARAM_EXT_SET_LEN); - memcpy(param_ext_set, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_param_ext_value.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_param_ext_value.h deleted file mode 100644 index e9384f0b..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_param_ext_value.h +++ /dev/null @@ -1,306 +0,0 @@ -#pragma once -// MESSAGE PARAM_EXT_VALUE PACKING - -#define MAVLINK_MSG_ID_PARAM_EXT_VALUE 322 - - -typedef struct __mavlink_param_ext_value_t { - uint16_t param_count; /*< Total number of parameters*/ - uint16_t param_index; /*< Index of this parameter*/ - char param_id[16]; /*< Parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string*/ - char param_value[128]; /*< Parameter value*/ - uint8_t param_type; /*< Parameter type.*/ -} mavlink_param_ext_value_t; - -#define MAVLINK_MSG_ID_PARAM_EXT_VALUE_LEN 149 -#define MAVLINK_MSG_ID_PARAM_EXT_VALUE_MIN_LEN 149 -#define MAVLINK_MSG_ID_322_LEN 149 -#define MAVLINK_MSG_ID_322_MIN_LEN 149 - -#define MAVLINK_MSG_ID_PARAM_EXT_VALUE_CRC 243 -#define MAVLINK_MSG_ID_322_CRC 243 - -#define MAVLINK_MSG_PARAM_EXT_VALUE_FIELD_PARAM_ID_LEN 16 -#define MAVLINK_MSG_PARAM_EXT_VALUE_FIELD_PARAM_VALUE_LEN 128 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_PARAM_EXT_VALUE { \ - 322, \ - "PARAM_EXT_VALUE", \ - 5, \ - { { "param_id", NULL, MAVLINK_TYPE_CHAR, 16, 4, offsetof(mavlink_param_ext_value_t, param_id) }, \ - { "param_value", NULL, MAVLINK_TYPE_CHAR, 128, 20, offsetof(mavlink_param_ext_value_t, param_value) }, \ - { "param_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 148, offsetof(mavlink_param_ext_value_t, param_type) }, \ - { "param_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_param_ext_value_t, param_count) }, \ - { "param_index", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_param_ext_value_t, param_index) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_PARAM_EXT_VALUE { \ - "PARAM_EXT_VALUE", \ - 5, \ - { { "param_id", NULL, MAVLINK_TYPE_CHAR, 16, 4, offsetof(mavlink_param_ext_value_t, param_id) }, \ - { "param_value", NULL, MAVLINK_TYPE_CHAR, 128, 20, offsetof(mavlink_param_ext_value_t, param_value) }, \ - { "param_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 148, offsetof(mavlink_param_ext_value_t, param_type) }, \ - { "param_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_param_ext_value_t, param_count) }, \ - { "param_index", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_param_ext_value_t, param_index) }, \ - } \ -} -#endif - -/** - * @brief Pack a param_ext_value message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param param_id Parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string - * @param param_value Parameter value - * @param param_type Parameter type. - * @param param_count Total number of parameters - * @param param_index Index of this parameter - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_param_ext_value_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - const char *param_id, const char *param_value, uint8_t param_type, uint16_t param_count, uint16_t param_index) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_PARAM_EXT_VALUE_LEN]; - _mav_put_uint16_t(buf, 0, param_count); - _mav_put_uint16_t(buf, 2, param_index); - _mav_put_uint8_t(buf, 148, param_type); - _mav_put_char_array(buf, 4, param_id, 16); - _mav_put_char_array(buf, 20, param_value, 128); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PARAM_EXT_VALUE_LEN); -#else - mavlink_param_ext_value_t packet; - packet.param_count = param_count; - packet.param_index = param_index; - packet.param_type = param_type; - mav_array_memcpy(packet.param_id, param_id, sizeof(char)*16); - mav_array_memcpy(packet.param_value, param_value, sizeof(char)*128); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PARAM_EXT_VALUE_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_PARAM_EXT_VALUE; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PARAM_EXT_VALUE_MIN_LEN, MAVLINK_MSG_ID_PARAM_EXT_VALUE_LEN, MAVLINK_MSG_ID_PARAM_EXT_VALUE_CRC); -} - -/** - * @brief Pack a param_ext_value message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param param_id Parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string - * @param param_value Parameter value - * @param param_type Parameter type. - * @param param_count Total number of parameters - * @param param_index Index of this parameter - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_param_ext_value_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - const char *param_id,const char *param_value,uint8_t param_type,uint16_t param_count,uint16_t param_index) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_PARAM_EXT_VALUE_LEN]; - _mav_put_uint16_t(buf, 0, param_count); - _mav_put_uint16_t(buf, 2, param_index); - _mav_put_uint8_t(buf, 148, param_type); - _mav_put_char_array(buf, 4, param_id, 16); - _mav_put_char_array(buf, 20, param_value, 128); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PARAM_EXT_VALUE_LEN); -#else - mavlink_param_ext_value_t packet; - packet.param_count = param_count; - packet.param_index = param_index; - packet.param_type = param_type; - mav_array_memcpy(packet.param_id, param_id, sizeof(char)*16); - mav_array_memcpy(packet.param_value, param_value, sizeof(char)*128); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PARAM_EXT_VALUE_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_PARAM_EXT_VALUE; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_PARAM_EXT_VALUE_MIN_LEN, MAVLINK_MSG_ID_PARAM_EXT_VALUE_LEN, MAVLINK_MSG_ID_PARAM_EXT_VALUE_CRC); -} - -/** - * @brief Encode a param_ext_value struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param param_ext_value C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_param_ext_value_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_param_ext_value_t* param_ext_value) -{ - return mavlink_msg_param_ext_value_pack(system_id, component_id, msg, param_ext_value->param_id, param_ext_value->param_value, param_ext_value->param_type, param_ext_value->param_count, param_ext_value->param_index); -} - -/** - * @brief Encode a param_ext_value struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param param_ext_value C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_param_ext_value_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_param_ext_value_t* param_ext_value) -{ - return mavlink_msg_param_ext_value_pack_chan(system_id, component_id, chan, msg, param_ext_value->param_id, param_ext_value->param_value, param_ext_value->param_type, param_ext_value->param_count, param_ext_value->param_index); -} - -/** - * @brief Send a param_ext_value message - * @param chan MAVLink channel to send the message - * - * @param param_id Parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string - * @param param_value Parameter value - * @param param_type Parameter type. - * @param param_count Total number of parameters - * @param param_index Index of this parameter - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_param_ext_value_send(mavlink_channel_t chan, const char *param_id, const char *param_value, uint8_t param_type, uint16_t param_count, uint16_t param_index) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_PARAM_EXT_VALUE_LEN]; - _mav_put_uint16_t(buf, 0, param_count); - _mav_put_uint16_t(buf, 2, param_index); - _mav_put_uint8_t(buf, 148, param_type); - _mav_put_char_array(buf, 4, param_id, 16); - _mav_put_char_array(buf, 20, param_value, 128); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_EXT_VALUE, buf, MAVLINK_MSG_ID_PARAM_EXT_VALUE_MIN_LEN, MAVLINK_MSG_ID_PARAM_EXT_VALUE_LEN, MAVLINK_MSG_ID_PARAM_EXT_VALUE_CRC); -#else - mavlink_param_ext_value_t packet; - packet.param_count = param_count; - packet.param_index = param_index; - packet.param_type = param_type; - mav_array_memcpy(packet.param_id, param_id, sizeof(char)*16); - mav_array_memcpy(packet.param_value, param_value, sizeof(char)*128); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_EXT_VALUE, (const char *)&packet, MAVLINK_MSG_ID_PARAM_EXT_VALUE_MIN_LEN, MAVLINK_MSG_ID_PARAM_EXT_VALUE_LEN, MAVLINK_MSG_ID_PARAM_EXT_VALUE_CRC); -#endif -} - -/** - * @brief Send a param_ext_value message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_param_ext_value_send_struct(mavlink_channel_t chan, const mavlink_param_ext_value_t* param_ext_value) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_param_ext_value_send(chan, param_ext_value->param_id, param_ext_value->param_value, param_ext_value->param_type, param_ext_value->param_count, param_ext_value->param_index); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_EXT_VALUE, (const char *)param_ext_value, MAVLINK_MSG_ID_PARAM_EXT_VALUE_MIN_LEN, MAVLINK_MSG_ID_PARAM_EXT_VALUE_LEN, MAVLINK_MSG_ID_PARAM_EXT_VALUE_CRC); -#endif -} - -#if MAVLINK_MSG_ID_PARAM_EXT_VALUE_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_param_ext_value_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, const char *param_id, const char *param_value, uint8_t param_type, uint16_t param_count, uint16_t param_index) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint16_t(buf, 0, param_count); - _mav_put_uint16_t(buf, 2, param_index); - _mav_put_uint8_t(buf, 148, param_type); - _mav_put_char_array(buf, 4, param_id, 16); - _mav_put_char_array(buf, 20, param_value, 128); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_EXT_VALUE, buf, MAVLINK_MSG_ID_PARAM_EXT_VALUE_MIN_LEN, MAVLINK_MSG_ID_PARAM_EXT_VALUE_LEN, MAVLINK_MSG_ID_PARAM_EXT_VALUE_CRC); -#else - mavlink_param_ext_value_t *packet = (mavlink_param_ext_value_t *)msgbuf; - packet->param_count = param_count; - packet->param_index = param_index; - packet->param_type = param_type; - mav_array_memcpy(packet->param_id, param_id, sizeof(char)*16); - mav_array_memcpy(packet->param_value, param_value, sizeof(char)*128); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_EXT_VALUE, (const char *)packet, MAVLINK_MSG_ID_PARAM_EXT_VALUE_MIN_LEN, MAVLINK_MSG_ID_PARAM_EXT_VALUE_LEN, MAVLINK_MSG_ID_PARAM_EXT_VALUE_CRC); -#endif -} -#endif - -#endif - -// MESSAGE PARAM_EXT_VALUE UNPACKING - - -/** - * @brief Get field param_id from param_ext_value message - * - * @return Parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string - */ -static inline uint16_t mavlink_msg_param_ext_value_get_param_id(const mavlink_message_t* msg, char *param_id) -{ - return _MAV_RETURN_char_array(msg, param_id, 16, 4); -} - -/** - * @brief Get field param_value from param_ext_value message - * - * @return Parameter value - */ -static inline uint16_t mavlink_msg_param_ext_value_get_param_value(const mavlink_message_t* msg, char *param_value) -{ - return _MAV_RETURN_char_array(msg, param_value, 128, 20); -} - -/** - * @brief Get field param_type from param_ext_value message - * - * @return Parameter type. - */ -static inline uint8_t mavlink_msg_param_ext_value_get_param_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 148); -} - -/** - * @brief Get field param_count from param_ext_value message - * - * @return Total number of parameters - */ -static inline uint16_t mavlink_msg_param_ext_value_get_param_count(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 0); -} - -/** - * @brief Get field param_index from param_ext_value message - * - * @return Index of this parameter - */ -static inline uint16_t mavlink_msg_param_ext_value_get_param_index(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 2); -} - -/** - * @brief Decode a param_ext_value message into a struct - * - * @param msg The message to decode - * @param param_ext_value C-struct to decode the message contents into - */ -static inline void mavlink_msg_param_ext_value_decode(const mavlink_message_t* msg, mavlink_param_ext_value_t* param_ext_value) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - param_ext_value->param_count = mavlink_msg_param_ext_value_get_param_count(msg); - param_ext_value->param_index = mavlink_msg_param_ext_value_get_param_index(msg); - mavlink_msg_param_ext_value_get_param_id(msg, param_ext_value->param_id); - mavlink_msg_param_ext_value_get_param_value(msg, param_ext_value->param_value); - param_ext_value->param_type = mavlink_msg_param_ext_value_get_param_type(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_PARAM_EXT_VALUE_LEN? msg->len : MAVLINK_MSG_ID_PARAM_EXT_VALUE_LEN; - memset(param_ext_value, 0, MAVLINK_MSG_ID_PARAM_EXT_VALUE_LEN); - memcpy(param_ext_value, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_param_map_rc.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_param_map_rc.h deleted file mode 100644 index 46fcaa19..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_param_map_rc.h +++ /dev/null @@ -1,405 +0,0 @@ -#pragma once -// MESSAGE PARAM_MAP_RC PACKING - -#define MAVLINK_MSG_ID_PARAM_MAP_RC 50 - - -typedef struct __mavlink_param_map_rc_t { - float param_value0; /*< Initial parameter value*/ - float scale; /*< Scale, maps the RC range [-1, 1] to a parameter value*/ - float param_value_min; /*< Minimum param value. The protocol does not define if this overwrites an onboard minimum value. (Depends on implementation)*/ - float param_value_max; /*< Maximum param value. The protocol does not define if this overwrites an onboard maximum value. (Depends on implementation)*/ - int16_t param_index; /*< Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored), send -2 to disable any existing map for this rc_channel_index.*/ - uint8_t target_system; /*< System ID*/ - uint8_t target_component; /*< Component ID*/ - char param_id[16]; /*< Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string*/ - uint8_t parameter_rc_channel_index; /*< Index of parameter RC channel. Not equal to the RC channel id. Typically corresponds to a potentiometer-knob on the RC.*/ -} mavlink_param_map_rc_t; - -#define MAVLINK_MSG_ID_PARAM_MAP_RC_LEN 37 -#define MAVLINK_MSG_ID_PARAM_MAP_RC_MIN_LEN 37 -#define MAVLINK_MSG_ID_50_LEN 37 -#define MAVLINK_MSG_ID_50_MIN_LEN 37 - -#define MAVLINK_MSG_ID_PARAM_MAP_RC_CRC 78 -#define MAVLINK_MSG_ID_50_CRC 78 - -#define MAVLINK_MSG_PARAM_MAP_RC_FIELD_PARAM_ID_LEN 16 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_PARAM_MAP_RC { \ - 50, \ - "PARAM_MAP_RC", \ - 9, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 18, offsetof(mavlink_param_map_rc_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 19, offsetof(mavlink_param_map_rc_t, target_component) }, \ - { "param_id", NULL, MAVLINK_TYPE_CHAR, 16, 20, offsetof(mavlink_param_map_rc_t, param_id) }, \ - { "param_index", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_param_map_rc_t, param_index) }, \ - { "parameter_rc_channel_index", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_param_map_rc_t, parameter_rc_channel_index) }, \ - { "param_value0", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_param_map_rc_t, param_value0) }, \ - { "scale", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_param_map_rc_t, scale) }, \ - { "param_value_min", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_param_map_rc_t, param_value_min) }, \ - { "param_value_max", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_param_map_rc_t, param_value_max) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_PARAM_MAP_RC { \ - "PARAM_MAP_RC", \ - 9, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 18, offsetof(mavlink_param_map_rc_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 19, offsetof(mavlink_param_map_rc_t, target_component) }, \ - { "param_id", NULL, MAVLINK_TYPE_CHAR, 16, 20, offsetof(mavlink_param_map_rc_t, param_id) }, \ - { "param_index", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_param_map_rc_t, param_index) }, \ - { "parameter_rc_channel_index", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_param_map_rc_t, parameter_rc_channel_index) }, \ - { "param_value0", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_param_map_rc_t, param_value0) }, \ - { "scale", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_param_map_rc_t, scale) }, \ - { "param_value_min", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_param_map_rc_t, param_value_min) }, \ - { "param_value_max", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_param_map_rc_t, param_value_max) }, \ - } \ -} -#endif - -/** - * @brief Pack a param_map_rc message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID - * @param target_component Component ID - * @param param_id Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string - * @param param_index Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored), send -2 to disable any existing map for this rc_channel_index. - * @param parameter_rc_channel_index Index of parameter RC channel. Not equal to the RC channel id. Typically corresponds to a potentiometer-knob on the RC. - * @param param_value0 Initial parameter value - * @param scale Scale, maps the RC range [-1, 1] to a parameter value - * @param param_value_min Minimum param value. The protocol does not define if this overwrites an onboard minimum value. (Depends on implementation) - * @param param_value_max Maximum param value. The protocol does not define if this overwrites an onboard maximum value. (Depends on implementation) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_param_map_rc_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component, const char *param_id, int16_t param_index, uint8_t parameter_rc_channel_index, float param_value0, float scale, float param_value_min, float param_value_max) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_PARAM_MAP_RC_LEN]; - _mav_put_float(buf, 0, param_value0); - _mav_put_float(buf, 4, scale); - _mav_put_float(buf, 8, param_value_min); - _mav_put_float(buf, 12, param_value_max); - _mav_put_int16_t(buf, 16, param_index); - _mav_put_uint8_t(buf, 18, target_system); - _mav_put_uint8_t(buf, 19, target_component); - _mav_put_uint8_t(buf, 36, parameter_rc_channel_index); - _mav_put_char_array(buf, 20, param_id, 16); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PARAM_MAP_RC_LEN); -#else - mavlink_param_map_rc_t packet; - packet.param_value0 = param_value0; - packet.scale = scale; - packet.param_value_min = param_value_min; - packet.param_value_max = param_value_max; - packet.param_index = param_index; - packet.target_system = target_system; - packet.target_component = target_component; - packet.parameter_rc_channel_index = parameter_rc_channel_index; - mav_array_memcpy(packet.param_id, param_id, sizeof(char)*16); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PARAM_MAP_RC_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_PARAM_MAP_RC; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PARAM_MAP_RC_MIN_LEN, MAVLINK_MSG_ID_PARAM_MAP_RC_LEN, MAVLINK_MSG_ID_PARAM_MAP_RC_CRC); -} - -/** - * @brief Pack a param_map_rc message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @param param_id Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string - * @param param_index Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored), send -2 to disable any existing map for this rc_channel_index. - * @param parameter_rc_channel_index Index of parameter RC channel. Not equal to the RC channel id. Typically corresponds to a potentiometer-knob on the RC. - * @param param_value0 Initial parameter value - * @param scale Scale, maps the RC range [-1, 1] to a parameter value - * @param param_value_min Minimum param value. The protocol does not define if this overwrites an onboard minimum value. (Depends on implementation) - * @param param_value_max Maximum param value. The protocol does not define if this overwrites an onboard maximum value. (Depends on implementation) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_param_map_rc_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component,const char *param_id,int16_t param_index,uint8_t parameter_rc_channel_index,float param_value0,float scale,float param_value_min,float param_value_max) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_PARAM_MAP_RC_LEN]; - _mav_put_float(buf, 0, param_value0); - _mav_put_float(buf, 4, scale); - _mav_put_float(buf, 8, param_value_min); - _mav_put_float(buf, 12, param_value_max); - _mav_put_int16_t(buf, 16, param_index); - _mav_put_uint8_t(buf, 18, target_system); - _mav_put_uint8_t(buf, 19, target_component); - _mav_put_uint8_t(buf, 36, parameter_rc_channel_index); - _mav_put_char_array(buf, 20, param_id, 16); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PARAM_MAP_RC_LEN); -#else - mavlink_param_map_rc_t packet; - packet.param_value0 = param_value0; - packet.scale = scale; - packet.param_value_min = param_value_min; - packet.param_value_max = param_value_max; - packet.param_index = param_index; - packet.target_system = target_system; - packet.target_component = target_component; - packet.parameter_rc_channel_index = parameter_rc_channel_index; - mav_array_memcpy(packet.param_id, param_id, sizeof(char)*16); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PARAM_MAP_RC_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_PARAM_MAP_RC; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_PARAM_MAP_RC_MIN_LEN, MAVLINK_MSG_ID_PARAM_MAP_RC_LEN, MAVLINK_MSG_ID_PARAM_MAP_RC_CRC); -} - -/** - * @brief Encode a param_map_rc struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param param_map_rc C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_param_map_rc_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_param_map_rc_t* param_map_rc) -{ - return mavlink_msg_param_map_rc_pack(system_id, component_id, msg, param_map_rc->target_system, param_map_rc->target_component, param_map_rc->param_id, param_map_rc->param_index, param_map_rc->parameter_rc_channel_index, param_map_rc->param_value0, param_map_rc->scale, param_map_rc->param_value_min, param_map_rc->param_value_max); -} - -/** - * @brief Encode a param_map_rc struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param param_map_rc C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_param_map_rc_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_param_map_rc_t* param_map_rc) -{ - return mavlink_msg_param_map_rc_pack_chan(system_id, component_id, chan, msg, param_map_rc->target_system, param_map_rc->target_component, param_map_rc->param_id, param_map_rc->param_index, param_map_rc->parameter_rc_channel_index, param_map_rc->param_value0, param_map_rc->scale, param_map_rc->param_value_min, param_map_rc->param_value_max); -} - -/** - * @brief Send a param_map_rc message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param target_component Component ID - * @param param_id Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string - * @param param_index Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored), send -2 to disable any existing map for this rc_channel_index. - * @param parameter_rc_channel_index Index of parameter RC channel. Not equal to the RC channel id. Typically corresponds to a potentiometer-knob on the RC. - * @param param_value0 Initial parameter value - * @param scale Scale, maps the RC range [-1, 1] to a parameter value - * @param param_value_min Minimum param value. The protocol does not define if this overwrites an onboard minimum value. (Depends on implementation) - * @param param_value_max Maximum param value. The protocol does not define if this overwrites an onboard maximum value. (Depends on implementation) - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_param_map_rc_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, const char *param_id, int16_t param_index, uint8_t parameter_rc_channel_index, float param_value0, float scale, float param_value_min, float param_value_max) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_PARAM_MAP_RC_LEN]; - _mav_put_float(buf, 0, param_value0); - _mav_put_float(buf, 4, scale); - _mav_put_float(buf, 8, param_value_min); - _mav_put_float(buf, 12, param_value_max); - _mav_put_int16_t(buf, 16, param_index); - _mav_put_uint8_t(buf, 18, target_system); - _mav_put_uint8_t(buf, 19, target_component); - _mav_put_uint8_t(buf, 36, parameter_rc_channel_index); - _mav_put_char_array(buf, 20, param_id, 16); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_MAP_RC, buf, MAVLINK_MSG_ID_PARAM_MAP_RC_MIN_LEN, MAVLINK_MSG_ID_PARAM_MAP_RC_LEN, MAVLINK_MSG_ID_PARAM_MAP_RC_CRC); -#else - mavlink_param_map_rc_t packet; - packet.param_value0 = param_value0; - packet.scale = scale; - packet.param_value_min = param_value_min; - packet.param_value_max = param_value_max; - packet.param_index = param_index; - packet.target_system = target_system; - packet.target_component = target_component; - packet.parameter_rc_channel_index = parameter_rc_channel_index; - mav_array_memcpy(packet.param_id, param_id, sizeof(char)*16); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_MAP_RC, (const char *)&packet, MAVLINK_MSG_ID_PARAM_MAP_RC_MIN_LEN, MAVLINK_MSG_ID_PARAM_MAP_RC_LEN, MAVLINK_MSG_ID_PARAM_MAP_RC_CRC); -#endif -} - -/** - * @brief Send a param_map_rc message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_param_map_rc_send_struct(mavlink_channel_t chan, const mavlink_param_map_rc_t* param_map_rc) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_param_map_rc_send(chan, param_map_rc->target_system, param_map_rc->target_component, param_map_rc->param_id, param_map_rc->param_index, param_map_rc->parameter_rc_channel_index, param_map_rc->param_value0, param_map_rc->scale, param_map_rc->param_value_min, param_map_rc->param_value_max); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_MAP_RC, (const char *)param_map_rc, MAVLINK_MSG_ID_PARAM_MAP_RC_MIN_LEN, MAVLINK_MSG_ID_PARAM_MAP_RC_LEN, MAVLINK_MSG_ID_PARAM_MAP_RC_CRC); -#endif -} - -#if MAVLINK_MSG_ID_PARAM_MAP_RC_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_param_map_rc_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, const char *param_id, int16_t param_index, uint8_t parameter_rc_channel_index, float param_value0, float scale, float param_value_min, float param_value_max) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_float(buf, 0, param_value0); - _mav_put_float(buf, 4, scale); - _mav_put_float(buf, 8, param_value_min); - _mav_put_float(buf, 12, param_value_max); - _mav_put_int16_t(buf, 16, param_index); - _mav_put_uint8_t(buf, 18, target_system); - _mav_put_uint8_t(buf, 19, target_component); - _mav_put_uint8_t(buf, 36, parameter_rc_channel_index); - _mav_put_char_array(buf, 20, param_id, 16); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_MAP_RC, buf, MAVLINK_MSG_ID_PARAM_MAP_RC_MIN_LEN, MAVLINK_MSG_ID_PARAM_MAP_RC_LEN, MAVLINK_MSG_ID_PARAM_MAP_RC_CRC); -#else - mavlink_param_map_rc_t *packet = (mavlink_param_map_rc_t *)msgbuf; - packet->param_value0 = param_value0; - packet->scale = scale; - packet->param_value_min = param_value_min; - packet->param_value_max = param_value_max; - packet->param_index = param_index; - packet->target_system = target_system; - packet->target_component = target_component; - packet->parameter_rc_channel_index = parameter_rc_channel_index; - mav_array_memcpy(packet->param_id, param_id, sizeof(char)*16); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_MAP_RC, (const char *)packet, MAVLINK_MSG_ID_PARAM_MAP_RC_MIN_LEN, MAVLINK_MSG_ID_PARAM_MAP_RC_LEN, MAVLINK_MSG_ID_PARAM_MAP_RC_CRC); -#endif -} -#endif - -#endif - -// MESSAGE PARAM_MAP_RC UNPACKING - - -/** - * @brief Get field target_system from param_map_rc message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_param_map_rc_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 18); -} - -/** - * @brief Get field target_component from param_map_rc message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_param_map_rc_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 19); -} - -/** - * @brief Get field param_id from param_map_rc message - * - * @return Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string - */ -static inline uint16_t mavlink_msg_param_map_rc_get_param_id(const mavlink_message_t* msg, char *param_id) -{ - return _MAV_RETURN_char_array(msg, param_id, 16, 20); -} - -/** - * @brief Get field param_index from param_map_rc message - * - * @return Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored), send -2 to disable any existing map for this rc_channel_index. - */ -static inline int16_t mavlink_msg_param_map_rc_get_param_index(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 16); -} - -/** - * @brief Get field parameter_rc_channel_index from param_map_rc message - * - * @return Index of parameter RC channel. Not equal to the RC channel id. Typically corresponds to a potentiometer-knob on the RC. - */ -static inline uint8_t mavlink_msg_param_map_rc_get_parameter_rc_channel_index(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 36); -} - -/** - * @brief Get field param_value0 from param_map_rc message - * - * @return Initial parameter value - */ -static inline float mavlink_msg_param_map_rc_get_param_value0(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 0); -} - -/** - * @brief Get field scale from param_map_rc message - * - * @return Scale, maps the RC range [-1, 1] to a parameter value - */ -static inline float mavlink_msg_param_map_rc_get_scale(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 4); -} - -/** - * @brief Get field param_value_min from param_map_rc message - * - * @return Minimum param value. The protocol does not define if this overwrites an onboard minimum value. (Depends on implementation) - */ -static inline float mavlink_msg_param_map_rc_get_param_value_min(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field param_value_max from param_map_rc message - * - * @return Maximum param value. The protocol does not define if this overwrites an onboard maximum value. (Depends on implementation) - */ -static inline float mavlink_msg_param_map_rc_get_param_value_max(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Decode a param_map_rc message into a struct - * - * @param msg The message to decode - * @param param_map_rc C-struct to decode the message contents into - */ -static inline void mavlink_msg_param_map_rc_decode(const mavlink_message_t* msg, mavlink_param_map_rc_t* param_map_rc) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - param_map_rc->param_value0 = mavlink_msg_param_map_rc_get_param_value0(msg); - param_map_rc->scale = mavlink_msg_param_map_rc_get_scale(msg); - param_map_rc->param_value_min = mavlink_msg_param_map_rc_get_param_value_min(msg); - param_map_rc->param_value_max = mavlink_msg_param_map_rc_get_param_value_max(msg); - param_map_rc->param_index = mavlink_msg_param_map_rc_get_param_index(msg); - param_map_rc->target_system = mavlink_msg_param_map_rc_get_target_system(msg); - param_map_rc->target_component = mavlink_msg_param_map_rc_get_target_component(msg); - mavlink_msg_param_map_rc_get_param_id(msg, param_map_rc->param_id); - param_map_rc->parameter_rc_channel_index = mavlink_msg_param_map_rc_get_parameter_rc_channel_index(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_PARAM_MAP_RC_LEN? msg->len : MAVLINK_MSG_ID_PARAM_MAP_RC_LEN; - memset(param_map_rc, 0, MAVLINK_MSG_ID_PARAM_MAP_RC_LEN); - memcpy(param_map_rc, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_param_request_list.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_param_request_list.h deleted file mode 100644 index 7ccfc87b..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_param_request_list.h +++ /dev/null @@ -1,238 +0,0 @@ -#pragma once -// MESSAGE PARAM_REQUEST_LIST PACKING - -#define MAVLINK_MSG_ID_PARAM_REQUEST_LIST 21 - - -typedef struct __mavlink_param_request_list_t { - uint8_t target_system; /*< System ID*/ - uint8_t target_component; /*< Component ID*/ -} mavlink_param_request_list_t; - -#define MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN 2 -#define MAVLINK_MSG_ID_PARAM_REQUEST_LIST_MIN_LEN 2 -#define MAVLINK_MSG_ID_21_LEN 2 -#define MAVLINK_MSG_ID_21_MIN_LEN 2 - -#define MAVLINK_MSG_ID_PARAM_REQUEST_LIST_CRC 159 -#define MAVLINK_MSG_ID_21_CRC 159 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_PARAM_REQUEST_LIST { \ - 21, \ - "PARAM_REQUEST_LIST", \ - 2, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_param_request_list_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_param_request_list_t, target_component) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_PARAM_REQUEST_LIST { \ - "PARAM_REQUEST_LIST", \ - 2, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_param_request_list_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_param_request_list_t, target_component) }, \ - } \ -} -#endif - -/** - * @brief Pack a param_request_list message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID - * @param target_component Component ID - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_param_request_list_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN]; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN); -#else - mavlink_param_request_list_t packet; - packet.target_system = target_system; - packet.target_component = target_component; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_PARAM_REQUEST_LIST; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_MIN_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_CRC); -} - -/** - * @brief Pack a param_request_list message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_param_request_list_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN]; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN); -#else - mavlink_param_request_list_t packet; - packet.target_system = target_system; - packet.target_component = target_component; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_PARAM_REQUEST_LIST; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_MIN_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_CRC); -} - -/** - * @brief Encode a param_request_list struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param param_request_list C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_param_request_list_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_param_request_list_t* param_request_list) -{ - return mavlink_msg_param_request_list_pack(system_id, component_id, msg, param_request_list->target_system, param_request_list->target_component); -} - -/** - * @brief Encode a param_request_list struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param param_request_list C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_param_request_list_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_param_request_list_t* param_request_list) -{ - return mavlink_msg_param_request_list_pack_chan(system_id, component_id, chan, msg, param_request_list->target_system, param_request_list->target_component); -} - -/** - * @brief Send a param_request_list message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param target_component Component ID - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_param_request_list_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN]; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_REQUEST_LIST, buf, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_MIN_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_CRC); -#else - mavlink_param_request_list_t packet; - packet.target_system = target_system; - packet.target_component = target_component; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_REQUEST_LIST, (const char *)&packet, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_MIN_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_CRC); -#endif -} - -/** - * @brief Send a param_request_list message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_param_request_list_send_struct(mavlink_channel_t chan, const mavlink_param_request_list_t* param_request_list) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_param_request_list_send(chan, param_request_list->target_system, param_request_list->target_component); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_REQUEST_LIST, (const char *)param_request_list, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_MIN_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_CRC); -#endif -} - -#if MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_param_request_list_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_REQUEST_LIST, buf, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_MIN_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_CRC); -#else - mavlink_param_request_list_t *packet = (mavlink_param_request_list_t *)msgbuf; - packet->target_system = target_system; - packet->target_component = target_component; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_REQUEST_LIST, (const char *)packet, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_MIN_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_CRC); -#endif -} -#endif - -#endif - -// MESSAGE PARAM_REQUEST_LIST UNPACKING - - -/** - * @brief Get field target_system from param_request_list message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_param_request_list_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 0); -} - -/** - * @brief Get field target_component from param_request_list message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_param_request_list_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 1); -} - -/** - * @brief Decode a param_request_list message into a struct - * - * @param msg The message to decode - * @param param_request_list C-struct to decode the message contents into - */ -static inline void mavlink_msg_param_request_list_decode(const mavlink_message_t* msg, mavlink_param_request_list_t* param_request_list) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - param_request_list->target_system = mavlink_msg_param_request_list_get_target_system(msg); - param_request_list->target_component = mavlink_msg_param_request_list_get_target_component(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN? msg->len : MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN; - memset(param_request_list, 0, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN); - memcpy(param_request_list, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_param_request_read.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_param_request_read.h deleted file mode 100644 index fa71a491..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_param_request_read.h +++ /dev/null @@ -1,280 +0,0 @@ -#pragma once -// MESSAGE PARAM_REQUEST_READ PACKING - -#define MAVLINK_MSG_ID_PARAM_REQUEST_READ 20 - - -typedef struct __mavlink_param_request_read_t { - int16_t param_index; /*< Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored)*/ - uint8_t target_system; /*< System ID*/ - uint8_t target_component; /*< Component ID*/ - char param_id[16]; /*< Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string*/ -} mavlink_param_request_read_t; - -#define MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN 20 -#define MAVLINK_MSG_ID_PARAM_REQUEST_READ_MIN_LEN 20 -#define MAVLINK_MSG_ID_20_LEN 20 -#define MAVLINK_MSG_ID_20_MIN_LEN 20 - -#define MAVLINK_MSG_ID_PARAM_REQUEST_READ_CRC 214 -#define MAVLINK_MSG_ID_20_CRC 214 - -#define MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN 16 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_PARAM_REQUEST_READ { \ - 20, \ - "PARAM_REQUEST_READ", \ - 4, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_param_request_read_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_param_request_read_t, target_component) }, \ - { "param_id", NULL, MAVLINK_TYPE_CHAR, 16, 4, offsetof(mavlink_param_request_read_t, param_id) }, \ - { "param_index", NULL, MAVLINK_TYPE_INT16_T, 0, 0, offsetof(mavlink_param_request_read_t, param_index) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_PARAM_REQUEST_READ { \ - "PARAM_REQUEST_READ", \ - 4, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_param_request_read_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_param_request_read_t, target_component) }, \ - { "param_id", NULL, MAVLINK_TYPE_CHAR, 16, 4, offsetof(mavlink_param_request_read_t, param_id) }, \ - { "param_index", NULL, MAVLINK_TYPE_INT16_T, 0, 0, offsetof(mavlink_param_request_read_t, param_index) }, \ - } \ -} -#endif - -/** - * @brief Pack a param_request_read message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID - * @param target_component Component ID - * @param param_id Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string - * @param param_index Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_param_request_read_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component, const char *param_id, int16_t param_index) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN]; - _mav_put_int16_t(buf, 0, param_index); - _mav_put_uint8_t(buf, 2, target_system); - _mav_put_uint8_t(buf, 3, target_component); - _mav_put_char_array(buf, 4, param_id, 16); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN); -#else - mavlink_param_request_read_t packet; - packet.param_index = param_index; - packet.target_system = target_system; - packet.target_component = target_component; - mav_array_memcpy(packet.param_id, param_id, sizeof(char)*16); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_PARAM_REQUEST_READ; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PARAM_REQUEST_READ_MIN_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_READ_CRC); -} - -/** - * @brief Pack a param_request_read message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @param param_id Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string - * @param param_index Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_param_request_read_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component,const char *param_id,int16_t param_index) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN]; - _mav_put_int16_t(buf, 0, param_index); - _mav_put_uint8_t(buf, 2, target_system); - _mav_put_uint8_t(buf, 3, target_component); - _mav_put_char_array(buf, 4, param_id, 16); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN); -#else - mavlink_param_request_read_t packet; - packet.param_index = param_index; - packet.target_system = target_system; - packet.target_component = target_component; - mav_array_memcpy(packet.param_id, param_id, sizeof(char)*16); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_PARAM_REQUEST_READ; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_PARAM_REQUEST_READ_MIN_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_READ_CRC); -} - -/** - * @brief Encode a param_request_read struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param param_request_read C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_param_request_read_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_param_request_read_t* param_request_read) -{ - return mavlink_msg_param_request_read_pack(system_id, component_id, msg, param_request_read->target_system, param_request_read->target_component, param_request_read->param_id, param_request_read->param_index); -} - -/** - * @brief Encode a param_request_read struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param param_request_read C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_param_request_read_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_param_request_read_t* param_request_read) -{ - return mavlink_msg_param_request_read_pack_chan(system_id, component_id, chan, msg, param_request_read->target_system, param_request_read->target_component, param_request_read->param_id, param_request_read->param_index); -} - -/** - * @brief Send a param_request_read message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param target_component Component ID - * @param param_id Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string - * @param param_index Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored) - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_param_request_read_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, const char *param_id, int16_t param_index) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN]; - _mav_put_int16_t(buf, 0, param_index); - _mav_put_uint8_t(buf, 2, target_system); - _mav_put_uint8_t(buf, 3, target_component); - _mav_put_char_array(buf, 4, param_id, 16); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_REQUEST_READ, buf, MAVLINK_MSG_ID_PARAM_REQUEST_READ_MIN_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_READ_CRC); -#else - mavlink_param_request_read_t packet; - packet.param_index = param_index; - packet.target_system = target_system; - packet.target_component = target_component; - mav_array_memcpy(packet.param_id, param_id, sizeof(char)*16); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_REQUEST_READ, (const char *)&packet, MAVLINK_MSG_ID_PARAM_REQUEST_READ_MIN_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_READ_CRC); -#endif -} - -/** - * @brief Send a param_request_read message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_param_request_read_send_struct(mavlink_channel_t chan, const mavlink_param_request_read_t* param_request_read) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_param_request_read_send(chan, param_request_read->target_system, param_request_read->target_component, param_request_read->param_id, param_request_read->param_index); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_REQUEST_READ, (const char *)param_request_read, MAVLINK_MSG_ID_PARAM_REQUEST_READ_MIN_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_READ_CRC); -#endif -} - -#if MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_param_request_read_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, const char *param_id, int16_t param_index) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_int16_t(buf, 0, param_index); - _mav_put_uint8_t(buf, 2, target_system); - _mav_put_uint8_t(buf, 3, target_component); - _mav_put_char_array(buf, 4, param_id, 16); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_REQUEST_READ, buf, MAVLINK_MSG_ID_PARAM_REQUEST_READ_MIN_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_READ_CRC); -#else - mavlink_param_request_read_t *packet = (mavlink_param_request_read_t *)msgbuf; - packet->param_index = param_index; - packet->target_system = target_system; - packet->target_component = target_component; - mav_array_memcpy(packet->param_id, param_id, sizeof(char)*16); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_REQUEST_READ, (const char *)packet, MAVLINK_MSG_ID_PARAM_REQUEST_READ_MIN_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_READ_CRC); -#endif -} -#endif - -#endif - -// MESSAGE PARAM_REQUEST_READ UNPACKING - - -/** - * @brief Get field target_system from param_request_read message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_param_request_read_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 2); -} - -/** - * @brief Get field target_component from param_request_read message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_param_request_read_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 3); -} - -/** - * @brief Get field param_id from param_request_read message - * - * @return Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string - */ -static inline uint16_t mavlink_msg_param_request_read_get_param_id(const mavlink_message_t* msg, char *param_id) -{ - return _MAV_RETURN_char_array(msg, param_id, 16, 4); -} - -/** - * @brief Get field param_index from param_request_read message - * - * @return Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored) - */ -static inline int16_t mavlink_msg_param_request_read_get_param_index(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 0); -} - -/** - * @brief Decode a param_request_read message into a struct - * - * @param msg The message to decode - * @param param_request_read C-struct to decode the message contents into - */ -static inline void mavlink_msg_param_request_read_decode(const mavlink_message_t* msg, mavlink_param_request_read_t* param_request_read) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - param_request_read->param_index = mavlink_msg_param_request_read_get_param_index(msg); - param_request_read->target_system = mavlink_msg_param_request_read_get_target_system(msg); - param_request_read->target_component = mavlink_msg_param_request_read_get_target_component(msg); - mavlink_msg_param_request_read_get_param_id(msg, param_request_read->param_id); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN? msg->len : MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN; - memset(param_request_read, 0, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN); - memcpy(param_request_read, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_param_set.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_param_set.h deleted file mode 100644 index 36a2bd43..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_param_set.h +++ /dev/null @@ -1,305 +0,0 @@ -#pragma once -// MESSAGE PARAM_SET PACKING - -#define MAVLINK_MSG_ID_PARAM_SET 23 - - -typedef struct __mavlink_param_set_t { - float param_value; /*< Onboard parameter value*/ - uint8_t target_system; /*< System ID*/ - uint8_t target_component; /*< Component ID*/ - char param_id[16]; /*< Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string*/ - uint8_t param_type; /*< Onboard parameter type.*/ -} mavlink_param_set_t; - -#define MAVLINK_MSG_ID_PARAM_SET_LEN 23 -#define MAVLINK_MSG_ID_PARAM_SET_MIN_LEN 23 -#define MAVLINK_MSG_ID_23_LEN 23 -#define MAVLINK_MSG_ID_23_MIN_LEN 23 - -#define MAVLINK_MSG_ID_PARAM_SET_CRC 168 -#define MAVLINK_MSG_ID_23_CRC 168 - -#define MAVLINK_MSG_PARAM_SET_FIELD_PARAM_ID_LEN 16 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_PARAM_SET { \ - 23, \ - "PARAM_SET", \ - 5, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_param_set_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_param_set_t, target_component) }, \ - { "param_id", NULL, MAVLINK_TYPE_CHAR, 16, 6, offsetof(mavlink_param_set_t, param_id) }, \ - { "param_value", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_param_set_t, param_value) }, \ - { "param_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 22, offsetof(mavlink_param_set_t, param_type) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_PARAM_SET { \ - "PARAM_SET", \ - 5, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_param_set_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_param_set_t, target_component) }, \ - { "param_id", NULL, MAVLINK_TYPE_CHAR, 16, 6, offsetof(mavlink_param_set_t, param_id) }, \ - { "param_value", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_param_set_t, param_value) }, \ - { "param_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 22, offsetof(mavlink_param_set_t, param_type) }, \ - } \ -} -#endif - -/** - * @brief Pack a param_set message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID - * @param target_component Component ID - * @param param_id Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string - * @param param_value Onboard parameter value - * @param param_type Onboard parameter type. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_param_set_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component, const char *param_id, float param_value, uint8_t param_type) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_PARAM_SET_LEN]; - _mav_put_float(buf, 0, param_value); - _mav_put_uint8_t(buf, 4, target_system); - _mav_put_uint8_t(buf, 5, target_component); - _mav_put_uint8_t(buf, 22, param_type); - _mav_put_char_array(buf, 6, param_id, 16); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PARAM_SET_LEN); -#else - mavlink_param_set_t packet; - packet.param_value = param_value; - packet.target_system = target_system; - packet.target_component = target_component; - packet.param_type = param_type; - mav_array_memcpy(packet.param_id, param_id, sizeof(char)*16); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PARAM_SET_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_PARAM_SET; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PARAM_SET_MIN_LEN, MAVLINK_MSG_ID_PARAM_SET_LEN, MAVLINK_MSG_ID_PARAM_SET_CRC); -} - -/** - * @brief Pack a param_set message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @param param_id Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string - * @param param_value Onboard parameter value - * @param param_type Onboard parameter type. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_param_set_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component,const char *param_id,float param_value,uint8_t param_type) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_PARAM_SET_LEN]; - _mav_put_float(buf, 0, param_value); - _mav_put_uint8_t(buf, 4, target_system); - _mav_put_uint8_t(buf, 5, target_component); - _mav_put_uint8_t(buf, 22, param_type); - _mav_put_char_array(buf, 6, param_id, 16); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PARAM_SET_LEN); -#else - mavlink_param_set_t packet; - packet.param_value = param_value; - packet.target_system = target_system; - packet.target_component = target_component; - packet.param_type = param_type; - mav_array_memcpy(packet.param_id, param_id, sizeof(char)*16); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PARAM_SET_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_PARAM_SET; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_PARAM_SET_MIN_LEN, MAVLINK_MSG_ID_PARAM_SET_LEN, MAVLINK_MSG_ID_PARAM_SET_CRC); -} - -/** - * @brief Encode a param_set struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param param_set C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_param_set_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_param_set_t* param_set) -{ - return mavlink_msg_param_set_pack(system_id, component_id, msg, param_set->target_system, param_set->target_component, param_set->param_id, param_set->param_value, param_set->param_type); -} - -/** - * @brief Encode a param_set struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param param_set C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_param_set_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_param_set_t* param_set) -{ - return mavlink_msg_param_set_pack_chan(system_id, component_id, chan, msg, param_set->target_system, param_set->target_component, param_set->param_id, param_set->param_value, param_set->param_type); -} - -/** - * @brief Send a param_set message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param target_component Component ID - * @param param_id Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string - * @param param_value Onboard parameter value - * @param param_type Onboard parameter type. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_param_set_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, const char *param_id, float param_value, uint8_t param_type) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_PARAM_SET_LEN]; - _mav_put_float(buf, 0, param_value); - _mav_put_uint8_t(buf, 4, target_system); - _mav_put_uint8_t(buf, 5, target_component); - _mav_put_uint8_t(buf, 22, param_type); - _mav_put_char_array(buf, 6, param_id, 16); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_SET, buf, MAVLINK_MSG_ID_PARAM_SET_MIN_LEN, MAVLINK_MSG_ID_PARAM_SET_LEN, MAVLINK_MSG_ID_PARAM_SET_CRC); -#else - mavlink_param_set_t packet; - packet.param_value = param_value; - packet.target_system = target_system; - packet.target_component = target_component; - packet.param_type = param_type; - mav_array_memcpy(packet.param_id, param_id, sizeof(char)*16); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_SET, (const char *)&packet, MAVLINK_MSG_ID_PARAM_SET_MIN_LEN, MAVLINK_MSG_ID_PARAM_SET_LEN, MAVLINK_MSG_ID_PARAM_SET_CRC); -#endif -} - -/** - * @brief Send a param_set message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_param_set_send_struct(mavlink_channel_t chan, const mavlink_param_set_t* param_set) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_param_set_send(chan, param_set->target_system, param_set->target_component, param_set->param_id, param_set->param_value, param_set->param_type); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_SET, (const char *)param_set, MAVLINK_MSG_ID_PARAM_SET_MIN_LEN, MAVLINK_MSG_ID_PARAM_SET_LEN, MAVLINK_MSG_ID_PARAM_SET_CRC); -#endif -} - -#if MAVLINK_MSG_ID_PARAM_SET_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_param_set_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, const char *param_id, float param_value, uint8_t param_type) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_float(buf, 0, param_value); - _mav_put_uint8_t(buf, 4, target_system); - _mav_put_uint8_t(buf, 5, target_component); - _mav_put_uint8_t(buf, 22, param_type); - _mav_put_char_array(buf, 6, param_id, 16); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_SET, buf, MAVLINK_MSG_ID_PARAM_SET_MIN_LEN, MAVLINK_MSG_ID_PARAM_SET_LEN, MAVLINK_MSG_ID_PARAM_SET_CRC); -#else - mavlink_param_set_t *packet = (mavlink_param_set_t *)msgbuf; - packet->param_value = param_value; - packet->target_system = target_system; - packet->target_component = target_component; - packet->param_type = param_type; - mav_array_memcpy(packet->param_id, param_id, sizeof(char)*16); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_SET, (const char *)packet, MAVLINK_MSG_ID_PARAM_SET_MIN_LEN, MAVLINK_MSG_ID_PARAM_SET_LEN, MAVLINK_MSG_ID_PARAM_SET_CRC); -#endif -} -#endif - -#endif - -// MESSAGE PARAM_SET UNPACKING - - -/** - * @brief Get field target_system from param_set message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_param_set_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 4); -} - -/** - * @brief Get field target_component from param_set message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_param_set_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 5); -} - -/** - * @brief Get field param_id from param_set message - * - * @return Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string - */ -static inline uint16_t mavlink_msg_param_set_get_param_id(const mavlink_message_t* msg, char *param_id) -{ - return _MAV_RETURN_char_array(msg, param_id, 16, 6); -} - -/** - * @brief Get field param_value from param_set message - * - * @return Onboard parameter value - */ -static inline float mavlink_msg_param_set_get_param_value(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 0); -} - -/** - * @brief Get field param_type from param_set message - * - * @return Onboard parameter type. - */ -static inline uint8_t mavlink_msg_param_set_get_param_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 22); -} - -/** - * @brief Decode a param_set message into a struct - * - * @param msg The message to decode - * @param param_set C-struct to decode the message contents into - */ -static inline void mavlink_msg_param_set_decode(const mavlink_message_t* msg, mavlink_param_set_t* param_set) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - param_set->param_value = mavlink_msg_param_set_get_param_value(msg); - param_set->target_system = mavlink_msg_param_set_get_target_system(msg); - param_set->target_component = mavlink_msg_param_set_get_target_component(msg); - mavlink_msg_param_set_get_param_id(msg, param_set->param_id); - param_set->param_type = mavlink_msg_param_set_get_param_type(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_PARAM_SET_LEN? msg->len : MAVLINK_MSG_ID_PARAM_SET_LEN; - memset(param_set, 0, MAVLINK_MSG_ID_PARAM_SET_LEN); - memcpy(param_set, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_param_value.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_param_value.h deleted file mode 100644 index 58bf4c53..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_param_value.h +++ /dev/null @@ -1,305 +0,0 @@ -#pragma once -// MESSAGE PARAM_VALUE PACKING - -#define MAVLINK_MSG_ID_PARAM_VALUE 22 - - -typedef struct __mavlink_param_value_t { - float param_value; /*< Onboard parameter value*/ - uint16_t param_count; /*< Total number of onboard parameters*/ - uint16_t param_index; /*< Index of this onboard parameter*/ - char param_id[16]; /*< Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string*/ - uint8_t param_type; /*< Onboard parameter type.*/ -} mavlink_param_value_t; - -#define MAVLINK_MSG_ID_PARAM_VALUE_LEN 25 -#define MAVLINK_MSG_ID_PARAM_VALUE_MIN_LEN 25 -#define MAVLINK_MSG_ID_22_LEN 25 -#define MAVLINK_MSG_ID_22_MIN_LEN 25 - -#define MAVLINK_MSG_ID_PARAM_VALUE_CRC 220 -#define MAVLINK_MSG_ID_22_CRC 220 - -#define MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN 16 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_PARAM_VALUE { \ - 22, \ - "PARAM_VALUE", \ - 5, \ - { { "param_id", NULL, MAVLINK_TYPE_CHAR, 16, 8, offsetof(mavlink_param_value_t, param_id) }, \ - { "param_value", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_param_value_t, param_value) }, \ - { "param_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_param_value_t, param_type) }, \ - { "param_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_param_value_t, param_count) }, \ - { "param_index", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_param_value_t, param_index) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_PARAM_VALUE { \ - "PARAM_VALUE", \ - 5, \ - { { "param_id", NULL, MAVLINK_TYPE_CHAR, 16, 8, offsetof(mavlink_param_value_t, param_id) }, \ - { "param_value", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_param_value_t, param_value) }, \ - { "param_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_param_value_t, param_type) }, \ - { "param_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_param_value_t, param_count) }, \ - { "param_index", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_param_value_t, param_index) }, \ - } \ -} -#endif - -/** - * @brief Pack a param_value message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param param_id Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string - * @param param_value Onboard parameter value - * @param param_type Onboard parameter type. - * @param param_count Total number of onboard parameters - * @param param_index Index of this onboard parameter - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_param_value_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - const char *param_id, float param_value, uint8_t param_type, uint16_t param_count, uint16_t param_index) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_PARAM_VALUE_LEN]; - _mav_put_float(buf, 0, param_value); - _mav_put_uint16_t(buf, 4, param_count); - _mav_put_uint16_t(buf, 6, param_index); - _mav_put_uint8_t(buf, 24, param_type); - _mav_put_char_array(buf, 8, param_id, 16); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PARAM_VALUE_LEN); -#else - mavlink_param_value_t packet; - packet.param_value = param_value; - packet.param_count = param_count; - packet.param_index = param_index; - packet.param_type = param_type; - mav_array_memcpy(packet.param_id, param_id, sizeof(char)*16); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PARAM_VALUE_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_PARAM_VALUE; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PARAM_VALUE_MIN_LEN, MAVLINK_MSG_ID_PARAM_VALUE_LEN, MAVLINK_MSG_ID_PARAM_VALUE_CRC); -} - -/** - * @brief Pack a param_value message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param param_id Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string - * @param param_value Onboard parameter value - * @param param_type Onboard parameter type. - * @param param_count Total number of onboard parameters - * @param param_index Index of this onboard parameter - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_param_value_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - const char *param_id,float param_value,uint8_t param_type,uint16_t param_count,uint16_t param_index) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_PARAM_VALUE_LEN]; - _mav_put_float(buf, 0, param_value); - _mav_put_uint16_t(buf, 4, param_count); - _mav_put_uint16_t(buf, 6, param_index); - _mav_put_uint8_t(buf, 24, param_type); - _mav_put_char_array(buf, 8, param_id, 16); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PARAM_VALUE_LEN); -#else - mavlink_param_value_t packet; - packet.param_value = param_value; - packet.param_count = param_count; - packet.param_index = param_index; - packet.param_type = param_type; - mav_array_memcpy(packet.param_id, param_id, sizeof(char)*16); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PARAM_VALUE_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_PARAM_VALUE; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_PARAM_VALUE_MIN_LEN, MAVLINK_MSG_ID_PARAM_VALUE_LEN, MAVLINK_MSG_ID_PARAM_VALUE_CRC); -} - -/** - * @brief Encode a param_value struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param param_value C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_param_value_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_param_value_t* param_value) -{ - return mavlink_msg_param_value_pack(system_id, component_id, msg, param_value->param_id, param_value->param_value, param_value->param_type, param_value->param_count, param_value->param_index); -} - -/** - * @brief Encode a param_value struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param param_value C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_param_value_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_param_value_t* param_value) -{ - return mavlink_msg_param_value_pack_chan(system_id, component_id, chan, msg, param_value->param_id, param_value->param_value, param_value->param_type, param_value->param_count, param_value->param_index); -} - -/** - * @brief Send a param_value message - * @param chan MAVLink channel to send the message - * - * @param param_id Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string - * @param param_value Onboard parameter value - * @param param_type Onboard parameter type. - * @param param_count Total number of onboard parameters - * @param param_index Index of this onboard parameter - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_param_value_send(mavlink_channel_t chan, const char *param_id, float param_value, uint8_t param_type, uint16_t param_count, uint16_t param_index) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_PARAM_VALUE_LEN]; - _mav_put_float(buf, 0, param_value); - _mav_put_uint16_t(buf, 4, param_count); - _mav_put_uint16_t(buf, 6, param_index); - _mav_put_uint8_t(buf, 24, param_type); - _mav_put_char_array(buf, 8, param_id, 16); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_VALUE, buf, MAVLINK_MSG_ID_PARAM_VALUE_MIN_LEN, MAVLINK_MSG_ID_PARAM_VALUE_LEN, MAVLINK_MSG_ID_PARAM_VALUE_CRC); -#else - mavlink_param_value_t packet; - packet.param_value = param_value; - packet.param_count = param_count; - packet.param_index = param_index; - packet.param_type = param_type; - mav_array_memcpy(packet.param_id, param_id, sizeof(char)*16); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_VALUE, (const char *)&packet, MAVLINK_MSG_ID_PARAM_VALUE_MIN_LEN, MAVLINK_MSG_ID_PARAM_VALUE_LEN, MAVLINK_MSG_ID_PARAM_VALUE_CRC); -#endif -} - -/** - * @brief Send a param_value message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_param_value_send_struct(mavlink_channel_t chan, const mavlink_param_value_t* param_value) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_param_value_send(chan, param_value->param_id, param_value->param_value, param_value->param_type, param_value->param_count, param_value->param_index); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_VALUE, (const char *)param_value, MAVLINK_MSG_ID_PARAM_VALUE_MIN_LEN, MAVLINK_MSG_ID_PARAM_VALUE_LEN, MAVLINK_MSG_ID_PARAM_VALUE_CRC); -#endif -} - -#if MAVLINK_MSG_ID_PARAM_VALUE_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_param_value_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, const char *param_id, float param_value, uint8_t param_type, uint16_t param_count, uint16_t param_index) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_float(buf, 0, param_value); - _mav_put_uint16_t(buf, 4, param_count); - _mav_put_uint16_t(buf, 6, param_index); - _mav_put_uint8_t(buf, 24, param_type); - _mav_put_char_array(buf, 8, param_id, 16); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_VALUE, buf, MAVLINK_MSG_ID_PARAM_VALUE_MIN_LEN, MAVLINK_MSG_ID_PARAM_VALUE_LEN, MAVLINK_MSG_ID_PARAM_VALUE_CRC); -#else - mavlink_param_value_t *packet = (mavlink_param_value_t *)msgbuf; - packet->param_value = param_value; - packet->param_count = param_count; - packet->param_index = param_index; - packet->param_type = param_type; - mav_array_memcpy(packet->param_id, param_id, sizeof(char)*16); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_VALUE, (const char *)packet, MAVLINK_MSG_ID_PARAM_VALUE_MIN_LEN, MAVLINK_MSG_ID_PARAM_VALUE_LEN, MAVLINK_MSG_ID_PARAM_VALUE_CRC); -#endif -} -#endif - -#endif - -// MESSAGE PARAM_VALUE UNPACKING - - -/** - * @brief Get field param_id from param_value message - * - * @return Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string - */ -static inline uint16_t mavlink_msg_param_value_get_param_id(const mavlink_message_t* msg, char *param_id) -{ - return _MAV_RETURN_char_array(msg, param_id, 16, 8); -} - -/** - * @brief Get field param_value from param_value message - * - * @return Onboard parameter value - */ -static inline float mavlink_msg_param_value_get_param_value(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 0); -} - -/** - * @brief Get field param_type from param_value message - * - * @return Onboard parameter type. - */ -static inline uint8_t mavlink_msg_param_value_get_param_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 24); -} - -/** - * @brief Get field param_count from param_value message - * - * @return Total number of onboard parameters - */ -static inline uint16_t mavlink_msg_param_value_get_param_count(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 4); -} - -/** - * @brief Get field param_index from param_value message - * - * @return Index of this onboard parameter - */ -static inline uint16_t mavlink_msg_param_value_get_param_index(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 6); -} - -/** - * @brief Decode a param_value message into a struct - * - * @param msg The message to decode - * @param param_value C-struct to decode the message contents into - */ -static inline void mavlink_msg_param_value_decode(const mavlink_message_t* msg, mavlink_param_value_t* param_value) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - param_value->param_value = mavlink_msg_param_value_get_param_value(msg); - param_value->param_count = mavlink_msg_param_value_get_param_count(msg); - param_value->param_index = mavlink_msg_param_value_get_param_index(msg); - mavlink_msg_param_value_get_param_id(msg, param_value->param_id); - param_value->param_type = mavlink_msg_param_value_get_param_type(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_PARAM_VALUE_LEN? msg->len : MAVLINK_MSG_ID_PARAM_VALUE_LEN; - memset(param_value, 0, MAVLINK_MSG_ID_PARAM_VALUE_LEN); - memcpy(param_value, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_ping.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_ping.h deleted file mode 100644 index e91a9b29..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_ping.h +++ /dev/null @@ -1,288 +0,0 @@ -#pragma once -// MESSAGE PING PACKING - -#define MAVLINK_MSG_ID_PING 4 - - -typedef struct __mavlink_ping_t { - uint64_t time_usec; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/ - uint32_t seq; /*< PING sequence*/ - uint8_t target_system; /*< 0: request ping from all receiving systems. If greater than 0: message is a ping response and number is the system id of the requesting system*/ - uint8_t target_component; /*< 0: request ping from all receiving components. If greater than 0: message is a ping response and number is the component id of the requesting component.*/ -} mavlink_ping_t; - -#define MAVLINK_MSG_ID_PING_LEN 14 -#define MAVLINK_MSG_ID_PING_MIN_LEN 14 -#define MAVLINK_MSG_ID_4_LEN 14 -#define MAVLINK_MSG_ID_4_MIN_LEN 14 - -#define MAVLINK_MSG_ID_PING_CRC 237 -#define MAVLINK_MSG_ID_4_CRC 237 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_PING { \ - 4, \ - "PING", \ - 4, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_ping_t, time_usec) }, \ - { "seq", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_ping_t, seq) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_ping_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 13, offsetof(mavlink_ping_t, target_component) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_PING { \ - "PING", \ - 4, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_ping_t, time_usec) }, \ - { "seq", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_ping_t, seq) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_ping_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 13, offsetof(mavlink_ping_t, target_component) }, \ - } \ -} -#endif - -/** - * @brief Pack a ping message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @param seq PING sequence - * @param target_system 0: request ping from all receiving systems. If greater than 0: message is a ping response and number is the system id of the requesting system - * @param target_component 0: request ping from all receiving components. If greater than 0: message is a ping response and number is the component id of the requesting component. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_ping_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint64_t time_usec, uint32_t seq, uint8_t target_system, uint8_t target_component) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_PING_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint32_t(buf, 8, seq); - _mav_put_uint8_t(buf, 12, target_system); - _mav_put_uint8_t(buf, 13, target_component); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PING_LEN); -#else - mavlink_ping_t packet; - packet.time_usec = time_usec; - packet.seq = seq; - packet.target_system = target_system; - packet.target_component = target_component; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PING_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_PING; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PING_MIN_LEN, MAVLINK_MSG_ID_PING_LEN, MAVLINK_MSG_ID_PING_CRC); -} - -/** - * @brief Pack a ping message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @param seq PING sequence - * @param target_system 0: request ping from all receiving systems. If greater than 0: message is a ping response and number is the system id of the requesting system - * @param target_component 0: request ping from all receiving components. If greater than 0: message is a ping response and number is the component id of the requesting component. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_ping_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint64_t time_usec,uint32_t seq,uint8_t target_system,uint8_t target_component) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_PING_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint32_t(buf, 8, seq); - _mav_put_uint8_t(buf, 12, target_system); - _mav_put_uint8_t(buf, 13, target_component); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PING_LEN); -#else - mavlink_ping_t packet; - packet.time_usec = time_usec; - packet.seq = seq; - packet.target_system = target_system; - packet.target_component = target_component; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PING_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_PING; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_PING_MIN_LEN, MAVLINK_MSG_ID_PING_LEN, MAVLINK_MSG_ID_PING_CRC); -} - -/** - * @brief Encode a ping struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param ping C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_ping_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_ping_t* ping) -{ - return mavlink_msg_ping_pack(system_id, component_id, msg, ping->time_usec, ping->seq, ping->target_system, ping->target_component); -} - -/** - * @brief Encode a ping struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param ping C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_ping_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_ping_t* ping) -{ - return mavlink_msg_ping_pack_chan(system_id, component_id, chan, msg, ping->time_usec, ping->seq, ping->target_system, ping->target_component); -} - -/** - * @brief Send a ping message - * @param chan MAVLink channel to send the message - * - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @param seq PING sequence - * @param target_system 0: request ping from all receiving systems. If greater than 0: message is a ping response and number is the system id of the requesting system - * @param target_component 0: request ping from all receiving components. If greater than 0: message is a ping response and number is the component id of the requesting component. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_ping_send(mavlink_channel_t chan, uint64_t time_usec, uint32_t seq, uint8_t target_system, uint8_t target_component) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_PING_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint32_t(buf, 8, seq); - _mav_put_uint8_t(buf, 12, target_system); - _mav_put_uint8_t(buf, 13, target_component); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PING, buf, MAVLINK_MSG_ID_PING_MIN_LEN, MAVLINK_MSG_ID_PING_LEN, MAVLINK_MSG_ID_PING_CRC); -#else - mavlink_ping_t packet; - packet.time_usec = time_usec; - packet.seq = seq; - packet.target_system = target_system; - packet.target_component = target_component; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PING, (const char *)&packet, MAVLINK_MSG_ID_PING_MIN_LEN, MAVLINK_MSG_ID_PING_LEN, MAVLINK_MSG_ID_PING_CRC); -#endif -} - -/** - * @brief Send a ping message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_ping_send_struct(mavlink_channel_t chan, const mavlink_ping_t* ping) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_ping_send(chan, ping->time_usec, ping->seq, ping->target_system, ping->target_component); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PING, (const char *)ping, MAVLINK_MSG_ID_PING_MIN_LEN, MAVLINK_MSG_ID_PING_LEN, MAVLINK_MSG_ID_PING_CRC); -#endif -} - -#if MAVLINK_MSG_ID_PING_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_ping_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, uint32_t seq, uint8_t target_system, uint8_t target_component) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint32_t(buf, 8, seq); - _mav_put_uint8_t(buf, 12, target_system); - _mav_put_uint8_t(buf, 13, target_component); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PING, buf, MAVLINK_MSG_ID_PING_MIN_LEN, MAVLINK_MSG_ID_PING_LEN, MAVLINK_MSG_ID_PING_CRC); -#else - mavlink_ping_t *packet = (mavlink_ping_t *)msgbuf; - packet->time_usec = time_usec; - packet->seq = seq; - packet->target_system = target_system; - packet->target_component = target_component; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PING, (const char *)packet, MAVLINK_MSG_ID_PING_MIN_LEN, MAVLINK_MSG_ID_PING_LEN, MAVLINK_MSG_ID_PING_CRC); -#endif -} -#endif - -#endif - -// MESSAGE PING UNPACKING - - -/** - * @brief Get field time_usec from ping message - * - * @return [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - */ -static inline uint64_t mavlink_msg_ping_get_time_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field seq from ping message - * - * @return PING sequence - */ -static inline uint32_t mavlink_msg_ping_get_seq(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 8); -} - -/** - * @brief Get field target_system from ping message - * - * @return 0: request ping from all receiving systems. If greater than 0: message is a ping response and number is the system id of the requesting system - */ -static inline uint8_t mavlink_msg_ping_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 12); -} - -/** - * @brief Get field target_component from ping message - * - * @return 0: request ping from all receiving components. If greater than 0: message is a ping response and number is the component id of the requesting component. - */ -static inline uint8_t mavlink_msg_ping_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 13); -} - -/** - * @brief Decode a ping message into a struct - * - * @param msg The message to decode - * @param ping C-struct to decode the message contents into - */ -static inline void mavlink_msg_ping_decode(const mavlink_message_t* msg, mavlink_ping_t* ping) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - ping->time_usec = mavlink_msg_ping_get_time_usec(msg); - ping->seq = mavlink_msg_ping_get_seq(msg); - ping->target_system = mavlink_msg_ping_get_target_system(msg); - ping->target_component = mavlink_msg_ping_get_target_component(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_PING_LEN? msg->len : MAVLINK_MSG_ID_PING_LEN; - memset(ping, 0, MAVLINK_MSG_ID_PING_LEN); - memcpy(ping, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_play_tune.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_play_tune.h deleted file mode 100644 index dac305ec..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_play_tune.h +++ /dev/null @@ -1,281 +0,0 @@ -#pragma once -// MESSAGE PLAY_TUNE PACKING - -#define MAVLINK_MSG_ID_PLAY_TUNE 258 - - -typedef struct __mavlink_play_tune_t { - uint8_t target_system; /*< System ID*/ - uint8_t target_component; /*< Component ID*/ - char tune[30]; /*< tune in board specific format*/ - char tune2[200]; /*< tune extension (appended to tune)*/ -} mavlink_play_tune_t; - -#define MAVLINK_MSG_ID_PLAY_TUNE_LEN 232 -#define MAVLINK_MSG_ID_PLAY_TUNE_MIN_LEN 32 -#define MAVLINK_MSG_ID_258_LEN 232 -#define MAVLINK_MSG_ID_258_MIN_LEN 32 - -#define MAVLINK_MSG_ID_PLAY_TUNE_CRC 187 -#define MAVLINK_MSG_ID_258_CRC 187 - -#define MAVLINK_MSG_PLAY_TUNE_FIELD_TUNE_LEN 30 -#define MAVLINK_MSG_PLAY_TUNE_FIELD_TUNE2_LEN 200 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_PLAY_TUNE { \ - 258, \ - "PLAY_TUNE", \ - 4, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_play_tune_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_play_tune_t, target_component) }, \ - { "tune", NULL, MAVLINK_TYPE_CHAR, 30, 2, offsetof(mavlink_play_tune_t, tune) }, \ - { "tune2", NULL, MAVLINK_TYPE_CHAR, 200, 32, offsetof(mavlink_play_tune_t, tune2) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_PLAY_TUNE { \ - "PLAY_TUNE", \ - 4, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_play_tune_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_play_tune_t, target_component) }, \ - { "tune", NULL, MAVLINK_TYPE_CHAR, 30, 2, offsetof(mavlink_play_tune_t, tune) }, \ - { "tune2", NULL, MAVLINK_TYPE_CHAR, 200, 32, offsetof(mavlink_play_tune_t, tune2) }, \ - } \ -} -#endif - -/** - * @brief Pack a play_tune message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID - * @param target_component Component ID - * @param tune tune in board specific format - * @param tune2 tune extension (appended to tune) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_play_tune_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component, const char *tune, const char *tune2) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_PLAY_TUNE_LEN]; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - _mav_put_char_array(buf, 2, tune, 30); - _mav_put_char_array(buf, 32, tune2, 200); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PLAY_TUNE_LEN); -#else - mavlink_play_tune_t packet; - packet.target_system = target_system; - packet.target_component = target_component; - mav_array_memcpy(packet.tune, tune, sizeof(char)*30); - mav_array_memcpy(packet.tune2, tune2, sizeof(char)*200); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PLAY_TUNE_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_PLAY_TUNE; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PLAY_TUNE_MIN_LEN, MAVLINK_MSG_ID_PLAY_TUNE_LEN, MAVLINK_MSG_ID_PLAY_TUNE_CRC); -} - -/** - * @brief Pack a play_tune message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @param tune tune in board specific format - * @param tune2 tune extension (appended to tune) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_play_tune_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component,const char *tune,const char *tune2) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_PLAY_TUNE_LEN]; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - _mav_put_char_array(buf, 2, tune, 30); - _mav_put_char_array(buf, 32, tune2, 200); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PLAY_TUNE_LEN); -#else - mavlink_play_tune_t packet; - packet.target_system = target_system; - packet.target_component = target_component; - mav_array_memcpy(packet.tune, tune, sizeof(char)*30); - mav_array_memcpy(packet.tune2, tune2, sizeof(char)*200); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PLAY_TUNE_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_PLAY_TUNE; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_PLAY_TUNE_MIN_LEN, MAVLINK_MSG_ID_PLAY_TUNE_LEN, MAVLINK_MSG_ID_PLAY_TUNE_CRC); -} - -/** - * @brief Encode a play_tune struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param play_tune C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_play_tune_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_play_tune_t* play_tune) -{ - return mavlink_msg_play_tune_pack(system_id, component_id, msg, play_tune->target_system, play_tune->target_component, play_tune->tune, play_tune->tune2); -} - -/** - * @brief Encode a play_tune struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param play_tune C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_play_tune_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_play_tune_t* play_tune) -{ - return mavlink_msg_play_tune_pack_chan(system_id, component_id, chan, msg, play_tune->target_system, play_tune->target_component, play_tune->tune, play_tune->tune2); -} - -/** - * @brief Send a play_tune message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param target_component Component ID - * @param tune tune in board specific format - * @param tune2 tune extension (appended to tune) - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_play_tune_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, const char *tune, const char *tune2) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_PLAY_TUNE_LEN]; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - _mav_put_char_array(buf, 2, tune, 30); - _mav_put_char_array(buf, 32, tune2, 200); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PLAY_TUNE, buf, MAVLINK_MSG_ID_PLAY_TUNE_MIN_LEN, MAVLINK_MSG_ID_PLAY_TUNE_LEN, MAVLINK_MSG_ID_PLAY_TUNE_CRC); -#else - mavlink_play_tune_t packet; - packet.target_system = target_system; - packet.target_component = target_component; - mav_array_memcpy(packet.tune, tune, sizeof(char)*30); - mav_array_memcpy(packet.tune2, tune2, sizeof(char)*200); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PLAY_TUNE, (const char *)&packet, MAVLINK_MSG_ID_PLAY_TUNE_MIN_LEN, MAVLINK_MSG_ID_PLAY_TUNE_LEN, MAVLINK_MSG_ID_PLAY_TUNE_CRC); -#endif -} - -/** - * @brief Send a play_tune message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_play_tune_send_struct(mavlink_channel_t chan, const mavlink_play_tune_t* play_tune) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_play_tune_send(chan, play_tune->target_system, play_tune->target_component, play_tune->tune, play_tune->tune2); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PLAY_TUNE, (const char *)play_tune, MAVLINK_MSG_ID_PLAY_TUNE_MIN_LEN, MAVLINK_MSG_ID_PLAY_TUNE_LEN, MAVLINK_MSG_ID_PLAY_TUNE_CRC); -#endif -} - -#if MAVLINK_MSG_ID_PLAY_TUNE_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_play_tune_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, const char *tune, const char *tune2) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - _mav_put_char_array(buf, 2, tune, 30); - _mav_put_char_array(buf, 32, tune2, 200); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PLAY_TUNE, buf, MAVLINK_MSG_ID_PLAY_TUNE_MIN_LEN, MAVLINK_MSG_ID_PLAY_TUNE_LEN, MAVLINK_MSG_ID_PLAY_TUNE_CRC); -#else - mavlink_play_tune_t *packet = (mavlink_play_tune_t *)msgbuf; - packet->target_system = target_system; - packet->target_component = target_component; - mav_array_memcpy(packet->tune, tune, sizeof(char)*30); - mav_array_memcpy(packet->tune2, tune2, sizeof(char)*200); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PLAY_TUNE, (const char *)packet, MAVLINK_MSG_ID_PLAY_TUNE_MIN_LEN, MAVLINK_MSG_ID_PLAY_TUNE_LEN, MAVLINK_MSG_ID_PLAY_TUNE_CRC); -#endif -} -#endif - -#endif - -// MESSAGE PLAY_TUNE UNPACKING - - -/** - * @brief Get field target_system from play_tune message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_play_tune_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 0); -} - -/** - * @brief Get field target_component from play_tune message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_play_tune_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 1); -} - -/** - * @brief Get field tune from play_tune message - * - * @return tune in board specific format - */ -static inline uint16_t mavlink_msg_play_tune_get_tune(const mavlink_message_t* msg, char *tune) -{ - return _MAV_RETURN_char_array(msg, tune, 30, 2); -} - -/** - * @brief Get field tune2 from play_tune message - * - * @return tune extension (appended to tune) - */ -static inline uint16_t mavlink_msg_play_tune_get_tune2(const mavlink_message_t* msg, char *tune2) -{ - return _MAV_RETURN_char_array(msg, tune2, 200, 32); -} - -/** - * @brief Decode a play_tune message into a struct - * - * @param msg The message to decode - * @param play_tune C-struct to decode the message contents into - */ -static inline void mavlink_msg_play_tune_decode(const mavlink_message_t* msg, mavlink_play_tune_t* play_tune) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - play_tune->target_system = mavlink_msg_play_tune_get_target_system(msg); - play_tune->target_component = mavlink_msg_play_tune_get_target_component(msg); - mavlink_msg_play_tune_get_tune(msg, play_tune->tune); - mavlink_msg_play_tune_get_tune2(msg, play_tune->tune2); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_PLAY_TUNE_LEN? msg->len : MAVLINK_MSG_ID_PLAY_TUNE_LEN; - memset(play_tune, 0, MAVLINK_MSG_ID_PLAY_TUNE_LEN); - memcpy(play_tune, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_play_tune_v2.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_play_tune_v2.h deleted file mode 100644 index f71da0aa..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_play_tune_v2.h +++ /dev/null @@ -1,280 +0,0 @@ -#pragma once -// MESSAGE PLAY_TUNE_V2 PACKING - -#define MAVLINK_MSG_ID_PLAY_TUNE_V2 400 - - -typedef struct __mavlink_play_tune_v2_t { - uint32_t format; /*< Tune format*/ - uint8_t target_system; /*< System ID*/ - uint8_t target_component; /*< Component ID*/ - char tune[248]; /*< Tune definition as a NULL-terminated string.*/ -} mavlink_play_tune_v2_t; - -#define MAVLINK_MSG_ID_PLAY_TUNE_V2_LEN 254 -#define MAVLINK_MSG_ID_PLAY_TUNE_V2_MIN_LEN 254 -#define MAVLINK_MSG_ID_400_LEN 254 -#define MAVLINK_MSG_ID_400_MIN_LEN 254 - -#define MAVLINK_MSG_ID_PLAY_TUNE_V2_CRC 110 -#define MAVLINK_MSG_ID_400_CRC 110 - -#define MAVLINK_MSG_PLAY_TUNE_V2_FIELD_TUNE_LEN 248 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_PLAY_TUNE_V2 { \ - 400, \ - "PLAY_TUNE_V2", \ - 4, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_play_tune_v2_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_play_tune_v2_t, target_component) }, \ - { "format", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_play_tune_v2_t, format) }, \ - { "tune", NULL, MAVLINK_TYPE_CHAR, 248, 6, offsetof(mavlink_play_tune_v2_t, tune) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_PLAY_TUNE_V2 { \ - "PLAY_TUNE_V2", \ - 4, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_play_tune_v2_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_play_tune_v2_t, target_component) }, \ - { "format", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_play_tune_v2_t, format) }, \ - { "tune", NULL, MAVLINK_TYPE_CHAR, 248, 6, offsetof(mavlink_play_tune_v2_t, tune) }, \ - } \ -} -#endif - -/** - * @brief Pack a play_tune_v2 message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID - * @param target_component Component ID - * @param format Tune format - * @param tune Tune definition as a NULL-terminated string. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_play_tune_v2_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component, uint32_t format, const char *tune) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_PLAY_TUNE_V2_LEN]; - _mav_put_uint32_t(buf, 0, format); - _mav_put_uint8_t(buf, 4, target_system); - _mav_put_uint8_t(buf, 5, target_component); - _mav_put_char_array(buf, 6, tune, 248); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PLAY_TUNE_V2_LEN); -#else - mavlink_play_tune_v2_t packet; - packet.format = format; - packet.target_system = target_system; - packet.target_component = target_component; - mav_array_memcpy(packet.tune, tune, sizeof(char)*248); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PLAY_TUNE_V2_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_PLAY_TUNE_V2; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PLAY_TUNE_V2_MIN_LEN, MAVLINK_MSG_ID_PLAY_TUNE_V2_LEN, MAVLINK_MSG_ID_PLAY_TUNE_V2_CRC); -} - -/** - * @brief Pack a play_tune_v2 message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @param format Tune format - * @param tune Tune definition as a NULL-terminated string. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_play_tune_v2_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component,uint32_t format,const char *tune) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_PLAY_TUNE_V2_LEN]; - _mav_put_uint32_t(buf, 0, format); - _mav_put_uint8_t(buf, 4, target_system); - _mav_put_uint8_t(buf, 5, target_component); - _mav_put_char_array(buf, 6, tune, 248); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PLAY_TUNE_V2_LEN); -#else - mavlink_play_tune_v2_t packet; - packet.format = format; - packet.target_system = target_system; - packet.target_component = target_component; - mav_array_memcpy(packet.tune, tune, sizeof(char)*248); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PLAY_TUNE_V2_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_PLAY_TUNE_V2; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_PLAY_TUNE_V2_MIN_LEN, MAVLINK_MSG_ID_PLAY_TUNE_V2_LEN, MAVLINK_MSG_ID_PLAY_TUNE_V2_CRC); -} - -/** - * @brief Encode a play_tune_v2 struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param play_tune_v2 C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_play_tune_v2_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_play_tune_v2_t* play_tune_v2) -{ - return mavlink_msg_play_tune_v2_pack(system_id, component_id, msg, play_tune_v2->target_system, play_tune_v2->target_component, play_tune_v2->format, play_tune_v2->tune); -} - -/** - * @brief Encode a play_tune_v2 struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param play_tune_v2 C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_play_tune_v2_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_play_tune_v2_t* play_tune_v2) -{ - return mavlink_msg_play_tune_v2_pack_chan(system_id, component_id, chan, msg, play_tune_v2->target_system, play_tune_v2->target_component, play_tune_v2->format, play_tune_v2->tune); -} - -/** - * @brief Send a play_tune_v2 message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param target_component Component ID - * @param format Tune format - * @param tune Tune definition as a NULL-terminated string. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_play_tune_v2_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint32_t format, const char *tune) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_PLAY_TUNE_V2_LEN]; - _mav_put_uint32_t(buf, 0, format); - _mav_put_uint8_t(buf, 4, target_system); - _mav_put_uint8_t(buf, 5, target_component); - _mav_put_char_array(buf, 6, tune, 248); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PLAY_TUNE_V2, buf, MAVLINK_MSG_ID_PLAY_TUNE_V2_MIN_LEN, MAVLINK_MSG_ID_PLAY_TUNE_V2_LEN, MAVLINK_MSG_ID_PLAY_TUNE_V2_CRC); -#else - mavlink_play_tune_v2_t packet; - packet.format = format; - packet.target_system = target_system; - packet.target_component = target_component; - mav_array_memcpy(packet.tune, tune, sizeof(char)*248); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PLAY_TUNE_V2, (const char *)&packet, MAVLINK_MSG_ID_PLAY_TUNE_V2_MIN_LEN, MAVLINK_MSG_ID_PLAY_TUNE_V2_LEN, MAVLINK_MSG_ID_PLAY_TUNE_V2_CRC); -#endif -} - -/** - * @brief Send a play_tune_v2 message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_play_tune_v2_send_struct(mavlink_channel_t chan, const mavlink_play_tune_v2_t* play_tune_v2) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_play_tune_v2_send(chan, play_tune_v2->target_system, play_tune_v2->target_component, play_tune_v2->format, play_tune_v2->tune); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PLAY_TUNE_V2, (const char *)play_tune_v2, MAVLINK_MSG_ID_PLAY_TUNE_V2_MIN_LEN, MAVLINK_MSG_ID_PLAY_TUNE_V2_LEN, MAVLINK_MSG_ID_PLAY_TUNE_V2_CRC); -#endif -} - -#if MAVLINK_MSG_ID_PLAY_TUNE_V2_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_play_tune_v2_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint32_t format, const char *tune) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, format); - _mav_put_uint8_t(buf, 4, target_system); - _mav_put_uint8_t(buf, 5, target_component); - _mav_put_char_array(buf, 6, tune, 248); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PLAY_TUNE_V2, buf, MAVLINK_MSG_ID_PLAY_TUNE_V2_MIN_LEN, MAVLINK_MSG_ID_PLAY_TUNE_V2_LEN, MAVLINK_MSG_ID_PLAY_TUNE_V2_CRC); -#else - mavlink_play_tune_v2_t *packet = (mavlink_play_tune_v2_t *)msgbuf; - packet->format = format; - packet->target_system = target_system; - packet->target_component = target_component; - mav_array_memcpy(packet->tune, tune, sizeof(char)*248); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PLAY_TUNE_V2, (const char *)packet, MAVLINK_MSG_ID_PLAY_TUNE_V2_MIN_LEN, MAVLINK_MSG_ID_PLAY_TUNE_V2_LEN, MAVLINK_MSG_ID_PLAY_TUNE_V2_CRC); -#endif -} -#endif - -#endif - -// MESSAGE PLAY_TUNE_V2 UNPACKING - - -/** - * @brief Get field target_system from play_tune_v2 message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_play_tune_v2_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 4); -} - -/** - * @brief Get field target_component from play_tune_v2 message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_play_tune_v2_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 5); -} - -/** - * @brief Get field format from play_tune_v2 message - * - * @return Tune format - */ -static inline uint32_t mavlink_msg_play_tune_v2_get_format(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field tune from play_tune_v2 message - * - * @return Tune definition as a NULL-terminated string. - */ -static inline uint16_t mavlink_msg_play_tune_v2_get_tune(const mavlink_message_t* msg, char *tune) -{ - return _MAV_RETURN_char_array(msg, tune, 248, 6); -} - -/** - * @brief Decode a play_tune_v2 message into a struct - * - * @param msg The message to decode - * @param play_tune_v2 C-struct to decode the message contents into - */ -static inline void mavlink_msg_play_tune_v2_decode(const mavlink_message_t* msg, mavlink_play_tune_v2_t* play_tune_v2) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - play_tune_v2->format = mavlink_msg_play_tune_v2_get_format(msg); - play_tune_v2->target_system = mavlink_msg_play_tune_v2_get_target_system(msg); - play_tune_v2->target_component = mavlink_msg_play_tune_v2_get_target_component(msg); - mavlink_msg_play_tune_v2_get_tune(msg, play_tune_v2->tune); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_PLAY_TUNE_V2_LEN? msg->len : MAVLINK_MSG_ID_PLAY_TUNE_V2_LEN; - memset(play_tune_v2, 0, MAVLINK_MSG_ID_PLAY_TUNE_V2_LEN); - memcpy(play_tune_v2, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_position_target_global_int.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_position_target_global_int.h deleted file mode 100644 index bb619b50..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_position_target_global_int.h +++ /dev/null @@ -1,538 +0,0 @@ -#pragma once -// MESSAGE POSITION_TARGET_GLOBAL_INT PACKING - -#define MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT 87 - - -typedef struct __mavlink_position_target_global_int_t { - uint32_t time_boot_ms; /*< [ms] Timestamp (time since system boot). The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency.*/ - int32_t lat_int; /*< [degE7] X Position in WGS84 frame*/ - int32_t lon_int; /*< [degE7] Y Position in WGS84 frame*/ - float alt; /*< [m] Altitude (MSL, AGL or relative to home altitude, depending on frame)*/ - float vx; /*< [m/s] X velocity in NED frame*/ - float vy; /*< [m/s] Y velocity in NED frame*/ - float vz; /*< [m/s] Z velocity in NED frame*/ - float afx; /*< [m/s/s] X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N*/ - float afy; /*< [m/s/s] Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N*/ - float afz; /*< [m/s/s] Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N*/ - float yaw; /*< [rad] yaw setpoint*/ - float yaw_rate; /*< [rad/s] yaw rate setpoint*/ - uint16_t type_mask; /*< Bitmap to indicate which dimensions should be ignored by the vehicle.*/ - uint8_t coordinate_frame; /*< Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11*/ -} mavlink_position_target_global_int_t; - -#define MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN 51 -#define MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_MIN_LEN 51 -#define MAVLINK_MSG_ID_87_LEN 51 -#define MAVLINK_MSG_ID_87_MIN_LEN 51 - -#define MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_CRC 150 -#define MAVLINK_MSG_ID_87_CRC 150 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_POSITION_TARGET_GLOBAL_INT { \ - 87, \ - "POSITION_TARGET_GLOBAL_INT", \ - 14, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_position_target_global_int_t, time_boot_ms) }, \ - { "coordinate_frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 50, offsetof(mavlink_position_target_global_int_t, coordinate_frame) }, \ - { "type_mask", NULL, MAVLINK_TYPE_UINT16_T, 0, 48, offsetof(mavlink_position_target_global_int_t, type_mask) }, \ - { "lat_int", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_position_target_global_int_t, lat_int) }, \ - { "lon_int", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_position_target_global_int_t, lon_int) }, \ - { "alt", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_position_target_global_int_t, alt) }, \ - { "vx", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_position_target_global_int_t, vx) }, \ - { "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_position_target_global_int_t, vy) }, \ - { "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_position_target_global_int_t, vz) }, \ - { "afx", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_position_target_global_int_t, afx) }, \ - { "afy", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_position_target_global_int_t, afy) }, \ - { "afz", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_position_target_global_int_t, afz) }, \ - { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_position_target_global_int_t, yaw) }, \ - { "yaw_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_position_target_global_int_t, yaw_rate) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_POSITION_TARGET_GLOBAL_INT { \ - "POSITION_TARGET_GLOBAL_INT", \ - 14, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_position_target_global_int_t, time_boot_ms) }, \ - { "coordinate_frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 50, offsetof(mavlink_position_target_global_int_t, coordinate_frame) }, \ - { "type_mask", NULL, MAVLINK_TYPE_UINT16_T, 0, 48, offsetof(mavlink_position_target_global_int_t, type_mask) }, \ - { "lat_int", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_position_target_global_int_t, lat_int) }, \ - { "lon_int", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_position_target_global_int_t, lon_int) }, \ - { "alt", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_position_target_global_int_t, alt) }, \ - { "vx", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_position_target_global_int_t, vx) }, \ - { "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_position_target_global_int_t, vy) }, \ - { "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_position_target_global_int_t, vz) }, \ - { "afx", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_position_target_global_int_t, afx) }, \ - { "afy", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_position_target_global_int_t, afy) }, \ - { "afz", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_position_target_global_int_t, afz) }, \ - { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_position_target_global_int_t, yaw) }, \ - { "yaw_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_position_target_global_int_t, yaw_rate) }, \ - } \ -} -#endif - -/** - * @brief Pack a position_target_global_int message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param time_boot_ms [ms] Timestamp (time since system boot). The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency. - * @param coordinate_frame Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11 - * @param type_mask Bitmap to indicate which dimensions should be ignored by the vehicle. - * @param lat_int [degE7] X Position in WGS84 frame - * @param lon_int [degE7] Y Position in WGS84 frame - * @param alt [m] Altitude (MSL, AGL or relative to home altitude, depending on frame) - * @param vx [m/s] X velocity in NED frame - * @param vy [m/s] Y velocity in NED frame - * @param vz [m/s] Z velocity in NED frame - * @param afx [m/s/s] X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param afy [m/s/s] Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param afz [m/s/s] Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param yaw [rad] yaw setpoint - * @param yaw_rate [rad/s] yaw rate setpoint - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_position_target_global_int_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint32_t time_boot_ms, uint8_t coordinate_frame, uint16_t type_mask, int32_t lat_int, int32_t lon_int, float alt, float vx, float vy, float vz, float afx, float afy, float afz, float yaw, float yaw_rate) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_int32_t(buf, 4, lat_int); - _mav_put_int32_t(buf, 8, lon_int); - _mav_put_float(buf, 12, alt); - _mav_put_float(buf, 16, vx); - _mav_put_float(buf, 20, vy); - _mav_put_float(buf, 24, vz); - _mav_put_float(buf, 28, afx); - _mav_put_float(buf, 32, afy); - _mav_put_float(buf, 36, afz); - _mav_put_float(buf, 40, yaw); - _mav_put_float(buf, 44, yaw_rate); - _mav_put_uint16_t(buf, 48, type_mask); - _mav_put_uint8_t(buf, 50, coordinate_frame); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN); -#else - mavlink_position_target_global_int_t packet; - packet.time_boot_ms = time_boot_ms; - packet.lat_int = lat_int; - packet.lon_int = lon_int; - packet.alt = alt; - packet.vx = vx; - packet.vy = vy; - packet.vz = vz; - packet.afx = afx; - packet.afy = afy; - packet.afz = afz; - packet.yaw = yaw; - packet.yaw_rate = yaw_rate; - packet.type_mask = type_mask; - packet.coordinate_frame = coordinate_frame; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_MIN_LEN, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_CRC); -} - -/** - * @brief Pack a position_target_global_int message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_boot_ms [ms] Timestamp (time since system boot). The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency. - * @param coordinate_frame Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11 - * @param type_mask Bitmap to indicate which dimensions should be ignored by the vehicle. - * @param lat_int [degE7] X Position in WGS84 frame - * @param lon_int [degE7] Y Position in WGS84 frame - * @param alt [m] Altitude (MSL, AGL or relative to home altitude, depending on frame) - * @param vx [m/s] X velocity in NED frame - * @param vy [m/s] Y velocity in NED frame - * @param vz [m/s] Z velocity in NED frame - * @param afx [m/s/s] X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param afy [m/s/s] Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param afz [m/s/s] Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param yaw [rad] yaw setpoint - * @param yaw_rate [rad/s] yaw rate setpoint - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_position_target_global_int_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint32_t time_boot_ms,uint8_t coordinate_frame,uint16_t type_mask,int32_t lat_int,int32_t lon_int,float alt,float vx,float vy,float vz,float afx,float afy,float afz,float yaw,float yaw_rate) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_int32_t(buf, 4, lat_int); - _mav_put_int32_t(buf, 8, lon_int); - _mav_put_float(buf, 12, alt); - _mav_put_float(buf, 16, vx); - _mav_put_float(buf, 20, vy); - _mav_put_float(buf, 24, vz); - _mav_put_float(buf, 28, afx); - _mav_put_float(buf, 32, afy); - _mav_put_float(buf, 36, afz); - _mav_put_float(buf, 40, yaw); - _mav_put_float(buf, 44, yaw_rate); - _mav_put_uint16_t(buf, 48, type_mask); - _mav_put_uint8_t(buf, 50, coordinate_frame); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN); -#else - mavlink_position_target_global_int_t packet; - packet.time_boot_ms = time_boot_ms; - packet.lat_int = lat_int; - packet.lon_int = lon_int; - packet.alt = alt; - packet.vx = vx; - packet.vy = vy; - packet.vz = vz; - packet.afx = afx; - packet.afy = afy; - packet.afz = afz; - packet.yaw = yaw; - packet.yaw_rate = yaw_rate; - packet.type_mask = type_mask; - packet.coordinate_frame = coordinate_frame; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_MIN_LEN, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_CRC); -} - -/** - * @brief Encode a position_target_global_int struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param position_target_global_int C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_position_target_global_int_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_position_target_global_int_t* position_target_global_int) -{ - return mavlink_msg_position_target_global_int_pack(system_id, component_id, msg, position_target_global_int->time_boot_ms, position_target_global_int->coordinate_frame, position_target_global_int->type_mask, position_target_global_int->lat_int, position_target_global_int->lon_int, position_target_global_int->alt, position_target_global_int->vx, position_target_global_int->vy, position_target_global_int->vz, position_target_global_int->afx, position_target_global_int->afy, position_target_global_int->afz, position_target_global_int->yaw, position_target_global_int->yaw_rate); -} - -/** - * @brief Encode a position_target_global_int struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param position_target_global_int C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_position_target_global_int_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_position_target_global_int_t* position_target_global_int) -{ - return mavlink_msg_position_target_global_int_pack_chan(system_id, component_id, chan, msg, position_target_global_int->time_boot_ms, position_target_global_int->coordinate_frame, position_target_global_int->type_mask, position_target_global_int->lat_int, position_target_global_int->lon_int, position_target_global_int->alt, position_target_global_int->vx, position_target_global_int->vy, position_target_global_int->vz, position_target_global_int->afx, position_target_global_int->afy, position_target_global_int->afz, position_target_global_int->yaw, position_target_global_int->yaw_rate); -} - -/** - * @brief Send a position_target_global_int message - * @param chan MAVLink channel to send the message - * - * @param time_boot_ms [ms] Timestamp (time since system boot). The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency. - * @param coordinate_frame Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11 - * @param type_mask Bitmap to indicate which dimensions should be ignored by the vehicle. - * @param lat_int [degE7] X Position in WGS84 frame - * @param lon_int [degE7] Y Position in WGS84 frame - * @param alt [m] Altitude (MSL, AGL or relative to home altitude, depending on frame) - * @param vx [m/s] X velocity in NED frame - * @param vy [m/s] Y velocity in NED frame - * @param vz [m/s] Z velocity in NED frame - * @param afx [m/s/s] X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param afy [m/s/s] Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param afz [m/s/s] Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param yaw [rad] yaw setpoint - * @param yaw_rate [rad/s] yaw rate setpoint - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_position_target_global_int_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t coordinate_frame, uint16_t type_mask, int32_t lat_int, int32_t lon_int, float alt, float vx, float vy, float vz, float afx, float afy, float afz, float yaw, float yaw_rate) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_int32_t(buf, 4, lat_int); - _mav_put_int32_t(buf, 8, lon_int); - _mav_put_float(buf, 12, alt); - _mav_put_float(buf, 16, vx); - _mav_put_float(buf, 20, vy); - _mav_put_float(buf, 24, vz); - _mav_put_float(buf, 28, afx); - _mav_put_float(buf, 32, afy); - _mav_put_float(buf, 36, afz); - _mav_put_float(buf, 40, yaw); - _mav_put_float(buf, 44, yaw_rate); - _mav_put_uint16_t(buf, 48, type_mask); - _mav_put_uint8_t(buf, 50, coordinate_frame); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT, buf, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_MIN_LEN, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_CRC); -#else - mavlink_position_target_global_int_t packet; - packet.time_boot_ms = time_boot_ms; - packet.lat_int = lat_int; - packet.lon_int = lon_int; - packet.alt = alt; - packet.vx = vx; - packet.vy = vy; - packet.vz = vz; - packet.afx = afx; - packet.afy = afy; - packet.afz = afz; - packet.yaw = yaw; - packet.yaw_rate = yaw_rate; - packet.type_mask = type_mask; - packet.coordinate_frame = coordinate_frame; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT, (const char *)&packet, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_MIN_LEN, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_CRC); -#endif -} - -/** - * @brief Send a position_target_global_int message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_position_target_global_int_send_struct(mavlink_channel_t chan, const mavlink_position_target_global_int_t* position_target_global_int) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_position_target_global_int_send(chan, position_target_global_int->time_boot_ms, position_target_global_int->coordinate_frame, position_target_global_int->type_mask, position_target_global_int->lat_int, position_target_global_int->lon_int, position_target_global_int->alt, position_target_global_int->vx, position_target_global_int->vy, position_target_global_int->vz, position_target_global_int->afx, position_target_global_int->afy, position_target_global_int->afz, position_target_global_int->yaw, position_target_global_int->yaw_rate); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT, (const char *)position_target_global_int, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_MIN_LEN, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_CRC); -#endif -} - -#if MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_position_target_global_int_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t coordinate_frame, uint16_t type_mask, int32_t lat_int, int32_t lon_int, float alt, float vx, float vy, float vz, float afx, float afy, float afz, float yaw, float yaw_rate) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_int32_t(buf, 4, lat_int); - _mav_put_int32_t(buf, 8, lon_int); - _mav_put_float(buf, 12, alt); - _mav_put_float(buf, 16, vx); - _mav_put_float(buf, 20, vy); - _mav_put_float(buf, 24, vz); - _mav_put_float(buf, 28, afx); - _mav_put_float(buf, 32, afy); - _mav_put_float(buf, 36, afz); - _mav_put_float(buf, 40, yaw); - _mav_put_float(buf, 44, yaw_rate); - _mav_put_uint16_t(buf, 48, type_mask); - _mav_put_uint8_t(buf, 50, coordinate_frame); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT, buf, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_MIN_LEN, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_CRC); -#else - mavlink_position_target_global_int_t *packet = (mavlink_position_target_global_int_t *)msgbuf; - packet->time_boot_ms = time_boot_ms; - packet->lat_int = lat_int; - packet->lon_int = lon_int; - packet->alt = alt; - packet->vx = vx; - packet->vy = vy; - packet->vz = vz; - packet->afx = afx; - packet->afy = afy; - packet->afz = afz; - packet->yaw = yaw; - packet->yaw_rate = yaw_rate; - packet->type_mask = type_mask; - packet->coordinate_frame = coordinate_frame; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT, (const char *)packet, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_MIN_LEN, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_CRC); -#endif -} -#endif - -#endif - -// MESSAGE POSITION_TARGET_GLOBAL_INT UNPACKING - - -/** - * @brief Get field time_boot_ms from position_target_global_int message - * - * @return [ms] Timestamp (time since system boot). The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency. - */ -static inline uint32_t mavlink_msg_position_target_global_int_get_time_boot_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field coordinate_frame from position_target_global_int message - * - * @return Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11 - */ -static inline uint8_t mavlink_msg_position_target_global_int_get_coordinate_frame(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 50); -} - -/** - * @brief Get field type_mask from position_target_global_int message - * - * @return Bitmap to indicate which dimensions should be ignored by the vehicle. - */ -static inline uint16_t mavlink_msg_position_target_global_int_get_type_mask(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 48); -} - -/** - * @brief Get field lat_int from position_target_global_int message - * - * @return [degE7] X Position in WGS84 frame - */ -static inline int32_t mavlink_msg_position_target_global_int_get_lat_int(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 4); -} - -/** - * @brief Get field lon_int from position_target_global_int message - * - * @return [degE7] Y Position in WGS84 frame - */ -static inline int32_t mavlink_msg_position_target_global_int_get_lon_int(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 8); -} - -/** - * @brief Get field alt from position_target_global_int message - * - * @return [m] Altitude (MSL, AGL or relative to home altitude, depending on frame) - */ -static inline float mavlink_msg_position_target_global_int_get_alt(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field vx from position_target_global_int message - * - * @return [m/s] X velocity in NED frame - */ -static inline float mavlink_msg_position_target_global_int_get_vx(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field vy from position_target_global_int message - * - * @return [m/s] Y velocity in NED frame - */ -static inline float mavlink_msg_position_target_global_int_get_vy(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Get field vz from position_target_global_int message - * - * @return [m/s] Z velocity in NED frame - */ -static inline float mavlink_msg_position_target_global_int_get_vz(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Get field afx from position_target_global_int message - * - * @return [m/s/s] X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - */ -static inline float mavlink_msg_position_target_global_int_get_afx(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 28); -} - -/** - * @brief Get field afy from position_target_global_int message - * - * @return [m/s/s] Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - */ -static inline float mavlink_msg_position_target_global_int_get_afy(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 32); -} - -/** - * @brief Get field afz from position_target_global_int message - * - * @return [m/s/s] Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - */ -static inline float mavlink_msg_position_target_global_int_get_afz(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 36); -} - -/** - * @brief Get field yaw from position_target_global_int message - * - * @return [rad] yaw setpoint - */ -static inline float mavlink_msg_position_target_global_int_get_yaw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 40); -} - -/** - * @brief Get field yaw_rate from position_target_global_int message - * - * @return [rad/s] yaw rate setpoint - */ -static inline float mavlink_msg_position_target_global_int_get_yaw_rate(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 44); -} - -/** - * @brief Decode a position_target_global_int message into a struct - * - * @param msg The message to decode - * @param position_target_global_int C-struct to decode the message contents into - */ -static inline void mavlink_msg_position_target_global_int_decode(const mavlink_message_t* msg, mavlink_position_target_global_int_t* position_target_global_int) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - position_target_global_int->time_boot_ms = mavlink_msg_position_target_global_int_get_time_boot_ms(msg); - position_target_global_int->lat_int = mavlink_msg_position_target_global_int_get_lat_int(msg); - position_target_global_int->lon_int = mavlink_msg_position_target_global_int_get_lon_int(msg); - position_target_global_int->alt = mavlink_msg_position_target_global_int_get_alt(msg); - position_target_global_int->vx = mavlink_msg_position_target_global_int_get_vx(msg); - position_target_global_int->vy = mavlink_msg_position_target_global_int_get_vy(msg); - position_target_global_int->vz = mavlink_msg_position_target_global_int_get_vz(msg); - position_target_global_int->afx = mavlink_msg_position_target_global_int_get_afx(msg); - position_target_global_int->afy = mavlink_msg_position_target_global_int_get_afy(msg); - position_target_global_int->afz = mavlink_msg_position_target_global_int_get_afz(msg); - position_target_global_int->yaw = mavlink_msg_position_target_global_int_get_yaw(msg); - position_target_global_int->yaw_rate = mavlink_msg_position_target_global_int_get_yaw_rate(msg); - position_target_global_int->type_mask = mavlink_msg_position_target_global_int_get_type_mask(msg); - position_target_global_int->coordinate_frame = mavlink_msg_position_target_global_int_get_coordinate_frame(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN? msg->len : MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN; - memset(position_target_global_int, 0, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN); - memcpy(position_target_global_int, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_position_target_local_ned.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_position_target_local_ned.h deleted file mode 100644 index 6aa98aee..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_position_target_local_ned.h +++ /dev/null @@ -1,538 +0,0 @@ -#pragma once -// MESSAGE POSITION_TARGET_LOCAL_NED PACKING - -#define MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED 85 - - -typedef struct __mavlink_position_target_local_ned_t { - uint32_t time_boot_ms; /*< [ms] Timestamp (time since system boot).*/ - float x; /*< [m] X Position in NED frame*/ - float y; /*< [m] Y Position in NED frame*/ - float z; /*< [m] Z Position in NED frame (note, altitude is negative in NED)*/ - float vx; /*< [m/s] X velocity in NED frame*/ - float vy; /*< [m/s] Y velocity in NED frame*/ - float vz; /*< [m/s] Z velocity in NED frame*/ - float afx; /*< [m/s/s] X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N*/ - float afy; /*< [m/s/s] Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N*/ - float afz; /*< [m/s/s] Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N*/ - float yaw; /*< [rad] yaw setpoint*/ - float yaw_rate; /*< [rad/s] yaw rate setpoint*/ - uint16_t type_mask; /*< Bitmap to indicate which dimensions should be ignored by the vehicle.*/ - uint8_t coordinate_frame; /*< Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9*/ -} mavlink_position_target_local_ned_t; - -#define MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN 51 -#define MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_MIN_LEN 51 -#define MAVLINK_MSG_ID_85_LEN 51 -#define MAVLINK_MSG_ID_85_MIN_LEN 51 - -#define MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_CRC 140 -#define MAVLINK_MSG_ID_85_CRC 140 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_POSITION_TARGET_LOCAL_NED { \ - 85, \ - "POSITION_TARGET_LOCAL_NED", \ - 14, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_position_target_local_ned_t, time_boot_ms) }, \ - { "coordinate_frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 50, offsetof(mavlink_position_target_local_ned_t, coordinate_frame) }, \ - { "type_mask", NULL, MAVLINK_TYPE_UINT16_T, 0, 48, offsetof(mavlink_position_target_local_ned_t, type_mask) }, \ - { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_position_target_local_ned_t, x) }, \ - { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_position_target_local_ned_t, y) }, \ - { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_position_target_local_ned_t, z) }, \ - { "vx", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_position_target_local_ned_t, vx) }, \ - { "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_position_target_local_ned_t, vy) }, \ - { "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_position_target_local_ned_t, vz) }, \ - { "afx", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_position_target_local_ned_t, afx) }, \ - { "afy", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_position_target_local_ned_t, afy) }, \ - { "afz", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_position_target_local_ned_t, afz) }, \ - { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_position_target_local_ned_t, yaw) }, \ - { "yaw_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_position_target_local_ned_t, yaw_rate) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_POSITION_TARGET_LOCAL_NED { \ - "POSITION_TARGET_LOCAL_NED", \ - 14, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_position_target_local_ned_t, time_boot_ms) }, \ - { "coordinate_frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 50, offsetof(mavlink_position_target_local_ned_t, coordinate_frame) }, \ - { "type_mask", NULL, MAVLINK_TYPE_UINT16_T, 0, 48, offsetof(mavlink_position_target_local_ned_t, type_mask) }, \ - { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_position_target_local_ned_t, x) }, \ - { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_position_target_local_ned_t, y) }, \ - { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_position_target_local_ned_t, z) }, \ - { "vx", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_position_target_local_ned_t, vx) }, \ - { "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_position_target_local_ned_t, vy) }, \ - { "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_position_target_local_ned_t, vz) }, \ - { "afx", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_position_target_local_ned_t, afx) }, \ - { "afy", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_position_target_local_ned_t, afy) }, \ - { "afz", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_position_target_local_ned_t, afz) }, \ - { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_position_target_local_ned_t, yaw) }, \ - { "yaw_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_position_target_local_ned_t, yaw_rate) }, \ - } \ -} -#endif - -/** - * @brief Pack a position_target_local_ned message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param time_boot_ms [ms] Timestamp (time since system boot). - * @param coordinate_frame Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9 - * @param type_mask Bitmap to indicate which dimensions should be ignored by the vehicle. - * @param x [m] X Position in NED frame - * @param y [m] Y Position in NED frame - * @param z [m] Z Position in NED frame (note, altitude is negative in NED) - * @param vx [m/s] X velocity in NED frame - * @param vy [m/s] Y velocity in NED frame - * @param vz [m/s] Z velocity in NED frame - * @param afx [m/s/s] X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param afy [m/s/s] Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param afz [m/s/s] Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param yaw [rad] yaw setpoint - * @param yaw_rate [rad/s] yaw rate setpoint - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_position_target_local_ned_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint32_t time_boot_ms, uint8_t coordinate_frame, uint16_t type_mask, float x, float y, float z, float vx, float vy, float vz, float afx, float afy, float afz, float yaw, float yaw_rate) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, x); - _mav_put_float(buf, 8, y); - _mav_put_float(buf, 12, z); - _mav_put_float(buf, 16, vx); - _mav_put_float(buf, 20, vy); - _mav_put_float(buf, 24, vz); - _mav_put_float(buf, 28, afx); - _mav_put_float(buf, 32, afy); - _mav_put_float(buf, 36, afz); - _mav_put_float(buf, 40, yaw); - _mav_put_float(buf, 44, yaw_rate); - _mav_put_uint16_t(buf, 48, type_mask); - _mav_put_uint8_t(buf, 50, coordinate_frame); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN); -#else - mavlink_position_target_local_ned_t packet; - packet.time_boot_ms = time_boot_ms; - packet.x = x; - packet.y = y; - packet.z = z; - packet.vx = vx; - packet.vy = vy; - packet.vz = vz; - packet.afx = afx; - packet.afy = afy; - packet.afz = afz; - packet.yaw = yaw; - packet.yaw_rate = yaw_rate; - packet.type_mask = type_mask; - packet.coordinate_frame = coordinate_frame; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_MIN_LEN, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_CRC); -} - -/** - * @brief Pack a position_target_local_ned message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_boot_ms [ms] Timestamp (time since system boot). - * @param coordinate_frame Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9 - * @param type_mask Bitmap to indicate which dimensions should be ignored by the vehicle. - * @param x [m] X Position in NED frame - * @param y [m] Y Position in NED frame - * @param z [m] Z Position in NED frame (note, altitude is negative in NED) - * @param vx [m/s] X velocity in NED frame - * @param vy [m/s] Y velocity in NED frame - * @param vz [m/s] Z velocity in NED frame - * @param afx [m/s/s] X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param afy [m/s/s] Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param afz [m/s/s] Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param yaw [rad] yaw setpoint - * @param yaw_rate [rad/s] yaw rate setpoint - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_position_target_local_ned_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint32_t time_boot_ms,uint8_t coordinate_frame,uint16_t type_mask,float x,float y,float z,float vx,float vy,float vz,float afx,float afy,float afz,float yaw,float yaw_rate) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, x); - _mav_put_float(buf, 8, y); - _mav_put_float(buf, 12, z); - _mav_put_float(buf, 16, vx); - _mav_put_float(buf, 20, vy); - _mav_put_float(buf, 24, vz); - _mav_put_float(buf, 28, afx); - _mav_put_float(buf, 32, afy); - _mav_put_float(buf, 36, afz); - _mav_put_float(buf, 40, yaw); - _mav_put_float(buf, 44, yaw_rate); - _mav_put_uint16_t(buf, 48, type_mask); - _mav_put_uint8_t(buf, 50, coordinate_frame); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN); -#else - mavlink_position_target_local_ned_t packet; - packet.time_boot_ms = time_boot_ms; - packet.x = x; - packet.y = y; - packet.z = z; - packet.vx = vx; - packet.vy = vy; - packet.vz = vz; - packet.afx = afx; - packet.afy = afy; - packet.afz = afz; - packet.yaw = yaw; - packet.yaw_rate = yaw_rate; - packet.type_mask = type_mask; - packet.coordinate_frame = coordinate_frame; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_MIN_LEN, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_CRC); -} - -/** - * @brief Encode a position_target_local_ned struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param position_target_local_ned C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_position_target_local_ned_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_position_target_local_ned_t* position_target_local_ned) -{ - return mavlink_msg_position_target_local_ned_pack(system_id, component_id, msg, position_target_local_ned->time_boot_ms, position_target_local_ned->coordinate_frame, position_target_local_ned->type_mask, position_target_local_ned->x, position_target_local_ned->y, position_target_local_ned->z, position_target_local_ned->vx, position_target_local_ned->vy, position_target_local_ned->vz, position_target_local_ned->afx, position_target_local_ned->afy, position_target_local_ned->afz, position_target_local_ned->yaw, position_target_local_ned->yaw_rate); -} - -/** - * @brief Encode a position_target_local_ned struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param position_target_local_ned C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_position_target_local_ned_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_position_target_local_ned_t* position_target_local_ned) -{ - return mavlink_msg_position_target_local_ned_pack_chan(system_id, component_id, chan, msg, position_target_local_ned->time_boot_ms, position_target_local_ned->coordinate_frame, position_target_local_ned->type_mask, position_target_local_ned->x, position_target_local_ned->y, position_target_local_ned->z, position_target_local_ned->vx, position_target_local_ned->vy, position_target_local_ned->vz, position_target_local_ned->afx, position_target_local_ned->afy, position_target_local_ned->afz, position_target_local_ned->yaw, position_target_local_ned->yaw_rate); -} - -/** - * @brief Send a position_target_local_ned message - * @param chan MAVLink channel to send the message - * - * @param time_boot_ms [ms] Timestamp (time since system boot). - * @param coordinate_frame Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9 - * @param type_mask Bitmap to indicate which dimensions should be ignored by the vehicle. - * @param x [m] X Position in NED frame - * @param y [m] Y Position in NED frame - * @param z [m] Z Position in NED frame (note, altitude is negative in NED) - * @param vx [m/s] X velocity in NED frame - * @param vy [m/s] Y velocity in NED frame - * @param vz [m/s] Z velocity in NED frame - * @param afx [m/s/s] X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param afy [m/s/s] Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param afz [m/s/s] Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param yaw [rad] yaw setpoint - * @param yaw_rate [rad/s] yaw rate setpoint - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_position_target_local_ned_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t coordinate_frame, uint16_t type_mask, float x, float y, float z, float vx, float vy, float vz, float afx, float afy, float afz, float yaw, float yaw_rate) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, x); - _mav_put_float(buf, 8, y); - _mav_put_float(buf, 12, z); - _mav_put_float(buf, 16, vx); - _mav_put_float(buf, 20, vy); - _mav_put_float(buf, 24, vz); - _mav_put_float(buf, 28, afx); - _mav_put_float(buf, 32, afy); - _mav_put_float(buf, 36, afz); - _mav_put_float(buf, 40, yaw); - _mav_put_float(buf, 44, yaw_rate); - _mav_put_uint16_t(buf, 48, type_mask); - _mav_put_uint8_t(buf, 50, coordinate_frame); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED, buf, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_MIN_LEN, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_CRC); -#else - mavlink_position_target_local_ned_t packet; - packet.time_boot_ms = time_boot_ms; - packet.x = x; - packet.y = y; - packet.z = z; - packet.vx = vx; - packet.vy = vy; - packet.vz = vz; - packet.afx = afx; - packet.afy = afy; - packet.afz = afz; - packet.yaw = yaw; - packet.yaw_rate = yaw_rate; - packet.type_mask = type_mask; - packet.coordinate_frame = coordinate_frame; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED, (const char *)&packet, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_MIN_LEN, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_CRC); -#endif -} - -/** - * @brief Send a position_target_local_ned message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_position_target_local_ned_send_struct(mavlink_channel_t chan, const mavlink_position_target_local_ned_t* position_target_local_ned) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_position_target_local_ned_send(chan, position_target_local_ned->time_boot_ms, position_target_local_ned->coordinate_frame, position_target_local_ned->type_mask, position_target_local_ned->x, position_target_local_ned->y, position_target_local_ned->z, position_target_local_ned->vx, position_target_local_ned->vy, position_target_local_ned->vz, position_target_local_ned->afx, position_target_local_ned->afy, position_target_local_ned->afz, position_target_local_ned->yaw, position_target_local_ned->yaw_rate); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED, (const char *)position_target_local_ned, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_MIN_LEN, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_CRC); -#endif -} - -#if MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_position_target_local_ned_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t coordinate_frame, uint16_t type_mask, float x, float y, float z, float vx, float vy, float vz, float afx, float afy, float afz, float yaw, float yaw_rate) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, x); - _mav_put_float(buf, 8, y); - _mav_put_float(buf, 12, z); - _mav_put_float(buf, 16, vx); - _mav_put_float(buf, 20, vy); - _mav_put_float(buf, 24, vz); - _mav_put_float(buf, 28, afx); - _mav_put_float(buf, 32, afy); - _mav_put_float(buf, 36, afz); - _mav_put_float(buf, 40, yaw); - _mav_put_float(buf, 44, yaw_rate); - _mav_put_uint16_t(buf, 48, type_mask); - _mav_put_uint8_t(buf, 50, coordinate_frame); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED, buf, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_MIN_LEN, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_CRC); -#else - mavlink_position_target_local_ned_t *packet = (mavlink_position_target_local_ned_t *)msgbuf; - packet->time_boot_ms = time_boot_ms; - packet->x = x; - packet->y = y; - packet->z = z; - packet->vx = vx; - packet->vy = vy; - packet->vz = vz; - packet->afx = afx; - packet->afy = afy; - packet->afz = afz; - packet->yaw = yaw; - packet->yaw_rate = yaw_rate; - packet->type_mask = type_mask; - packet->coordinate_frame = coordinate_frame; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED, (const char *)packet, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_MIN_LEN, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_CRC); -#endif -} -#endif - -#endif - -// MESSAGE POSITION_TARGET_LOCAL_NED UNPACKING - - -/** - * @brief Get field time_boot_ms from position_target_local_ned message - * - * @return [ms] Timestamp (time since system boot). - */ -static inline uint32_t mavlink_msg_position_target_local_ned_get_time_boot_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field coordinate_frame from position_target_local_ned message - * - * @return Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9 - */ -static inline uint8_t mavlink_msg_position_target_local_ned_get_coordinate_frame(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 50); -} - -/** - * @brief Get field type_mask from position_target_local_ned message - * - * @return Bitmap to indicate which dimensions should be ignored by the vehicle. - */ -static inline uint16_t mavlink_msg_position_target_local_ned_get_type_mask(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 48); -} - -/** - * @brief Get field x from position_target_local_ned message - * - * @return [m] X Position in NED frame - */ -static inline float mavlink_msg_position_target_local_ned_get_x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 4); -} - -/** - * @brief Get field y from position_target_local_ned message - * - * @return [m] Y Position in NED frame - */ -static inline float mavlink_msg_position_target_local_ned_get_y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field z from position_target_local_ned message - * - * @return [m] Z Position in NED frame (note, altitude is negative in NED) - */ -static inline float mavlink_msg_position_target_local_ned_get_z(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field vx from position_target_local_ned message - * - * @return [m/s] X velocity in NED frame - */ -static inline float mavlink_msg_position_target_local_ned_get_vx(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field vy from position_target_local_ned message - * - * @return [m/s] Y velocity in NED frame - */ -static inline float mavlink_msg_position_target_local_ned_get_vy(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Get field vz from position_target_local_ned message - * - * @return [m/s] Z velocity in NED frame - */ -static inline float mavlink_msg_position_target_local_ned_get_vz(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Get field afx from position_target_local_ned message - * - * @return [m/s/s] X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - */ -static inline float mavlink_msg_position_target_local_ned_get_afx(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 28); -} - -/** - * @brief Get field afy from position_target_local_ned message - * - * @return [m/s/s] Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - */ -static inline float mavlink_msg_position_target_local_ned_get_afy(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 32); -} - -/** - * @brief Get field afz from position_target_local_ned message - * - * @return [m/s/s] Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - */ -static inline float mavlink_msg_position_target_local_ned_get_afz(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 36); -} - -/** - * @brief Get field yaw from position_target_local_ned message - * - * @return [rad] yaw setpoint - */ -static inline float mavlink_msg_position_target_local_ned_get_yaw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 40); -} - -/** - * @brief Get field yaw_rate from position_target_local_ned message - * - * @return [rad/s] yaw rate setpoint - */ -static inline float mavlink_msg_position_target_local_ned_get_yaw_rate(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 44); -} - -/** - * @brief Decode a position_target_local_ned message into a struct - * - * @param msg The message to decode - * @param position_target_local_ned C-struct to decode the message contents into - */ -static inline void mavlink_msg_position_target_local_ned_decode(const mavlink_message_t* msg, mavlink_position_target_local_ned_t* position_target_local_ned) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - position_target_local_ned->time_boot_ms = mavlink_msg_position_target_local_ned_get_time_boot_ms(msg); - position_target_local_ned->x = mavlink_msg_position_target_local_ned_get_x(msg); - position_target_local_ned->y = mavlink_msg_position_target_local_ned_get_y(msg); - position_target_local_ned->z = mavlink_msg_position_target_local_ned_get_z(msg); - position_target_local_ned->vx = mavlink_msg_position_target_local_ned_get_vx(msg); - position_target_local_ned->vy = mavlink_msg_position_target_local_ned_get_vy(msg); - position_target_local_ned->vz = mavlink_msg_position_target_local_ned_get_vz(msg); - position_target_local_ned->afx = mavlink_msg_position_target_local_ned_get_afx(msg); - position_target_local_ned->afy = mavlink_msg_position_target_local_ned_get_afy(msg); - position_target_local_ned->afz = mavlink_msg_position_target_local_ned_get_afz(msg); - position_target_local_ned->yaw = mavlink_msg_position_target_local_ned_get_yaw(msg); - position_target_local_ned->yaw_rate = mavlink_msg_position_target_local_ned_get_yaw_rate(msg); - position_target_local_ned->type_mask = mavlink_msg_position_target_local_ned_get_type_mask(msg); - position_target_local_ned->coordinate_frame = mavlink_msg_position_target_local_ned_get_coordinate_frame(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN? msg->len : MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN; - memset(position_target_local_ned, 0, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN); - memcpy(position_target_local_ned, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_power_status.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_power_status.h deleted file mode 100644 index a3cd2fe6..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_power_status.h +++ /dev/null @@ -1,263 +0,0 @@ -#pragma once -// MESSAGE POWER_STATUS PACKING - -#define MAVLINK_MSG_ID_POWER_STATUS 125 - - -typedef struct __mavlink_power_status_t { - uint16_t Vcc; /*< [mV] 5V rail voltage.*/ - uint16_t Vservo; /*< [mV] Servo rail voltage.*/ - uint16_t flags; /*< Bitmap of power supply status flags.*/ -} mavlink_power_status_t; - -#define MAVLINK_MSG_ID_POWER_STATUS_LEN 6 -#define MAVLINK_MSG_ID_POWER_STATUS_MIN_LEN 6 -#define MAVLINK_MSG_ID_125_LEN 6 -#define MAVLINK_MSG_ID_125_MIN_LEN 6 - -#define MAVLINK_MSG_ID_POWER_STATUS_CRC 203 -#define MAVLINK_MSG_ID_125_CRC 203 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_POWER_STATUS { \ - 125, \ - "POWER_STATUS", \ - 3, \ - { { "Vcc", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_power_status_t, Vcc) }, \ - { "Vservo", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_power_status_t, Vservo) }, \ - { "flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_power_status_t, flags) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_POWER_STATUS { \ - "POWER_STATUS", \ - 3, \ - { { "Vcc", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_power_status_t, Vcc) }, \ - { "Vservo", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_power_status_t, Vservo) }, \ - { "flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_power_status_t, flags) }, \ - } \ -} -#endif - -/** - * @brief Pack a power_status message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param Vcc [mV] 5V rail voltage. - * @param Vservo [mV] Servo rail voltage. - * @param flags Bitmap of power supply status flags. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_power_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint16_t Vcc, uint16_t Vservo, uint16_t flags) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_POWER_STATUS_LEN]; - _mav_put_uint16_t(buf, 0, Vcc); - _mav_put_uint16_t(buf, 2, Vservo); - _mav_put_uint16_t(buf, 4, flags); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_POWER_STATUS_LEN); -#else - mavlink_power_status_t packet; - packet.Vcc = Vcc; - packet.Vservo = Vservo; - packet.flags = flags; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_POWER_STATUS_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_POWER_STATUS; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_POWER_STATUS_MIN_LEN, MAVLINK_MSG_ID_POWER_STATUS_LEN, MAVLINK_MSG_ID_POWER_STATUS_CRC); -} - -/** - * @brief Pack a power_status message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param Vcc [mV] 5V rail voltage. - * @param Vservo [mV] Servo rail voltage. - * @param flags Bitmap of power supply status flags. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_power_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint16_t Vcc,uint16_t Vservo,uint16_t flags) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_POWER_STATUS_LEN]; - _mav_put_uint16_t(buf, 0, Vcc); - _mav_put_uint16_t(buf, 2, Vservo); - _mav_put_uint16_t(buf, 4, flags); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_POWER_STATUS_LEN); -#else - mavlink_power_status_t packet; - packet.Vcc = Vcc; - packet.Vservo = Vservo; - packet.flags = flags; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_POWER_STATUS_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_POWER_STATUS; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_POWER_STATUS_MIN_LEN, MAVLINK_MSG_ID_POWER_STATUS_LEN, MAVLINK_MSG_ID_POWER_STATUS_CRC); -} - -/** - * @brief Encode a power_status struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param power_status C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_power_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_power_status_t* power_status) -{ - return mavlink_msg_power_status_pack(system_id, component_id, msg, power_status->Vcc, power_status->Vservo, power_status->flags); -} - -/** - * @brief Encode a power_status struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param power_status C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_power_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_power_status_t* power_status) -{ - return mavlink_msg_power_status_pack_chan(system_id, component_id, chan, msg, power_status->Vcc, power_status->Vservo, power_status->flags); -} - -/** - * @brief Send a power_status message - * @param chan MAVLink channel to send the message - * - * @param Vcc [mV] 5V rail voltage. - * @param Vservo [mV] Servo rail voltage. - * @param flags Bitmap of power supply status flags. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_power_status_send(mavlink_channel_t chan, uint16_t Vcc, uint16_t Vservo, uint16_t flags) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_POWER_STATUS_LEN]; - _mav_put_uint16_t(buf, 0, Vcc); - _mav_put_uint16_t(buf, 2, Vservo); - _mav_put_uint16_t(buf, 4, flags); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POWER_STATUS, buf, MAVLINK_MSG_ID_POWER_STATUS_MIN_LEN, MAVLINK_MSG_ID_POWER_STATUS_LEN, MAVLINK_MSG_ID_POWER_STATUS_CRC); -#else - mavlink_power_status_t packet; - packet.Vcc = Vcc; - packet.Vservo = Vservo; - packet.flags = flags; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POWER_STATUS, (const char *)&packet, MAVLINK_MSG_ID_POWER_STATUS_MIN_LEN, MAVLINK_MSG_ID_POWER_STATUS_LEN, MAVLINK_MSG_ID_POWER_STATUS_CRC); -#endif -} - -/** - * @brief Send a power_status message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_power_status_send_struct(mavlink_channel_t chan, const mavlink_power_status_t* power_status) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_power_status_send(chan, power_status->Vcc, power_status->Vservo, power_status->flags); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POWER_STATUS, (const char *)power_status, MAVLINK_MSG_ID_POWER_STATUS_MIN_LEN, MAVLINK_MSG_ID_POWER_STATUS_LEN, MAVLINK_MSG_ID_POWER_STATUS_CRC); -#endif -} - -#if MAVLINK_MSG_ID_POWER_STATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_power_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint16_t Vcc, uint16_t Vservo, uint16_t flags) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint16_t(buf, 0, Vcc); - _mav_put_uint16_t(buf, 2, Vservo); - _mav_put_uint16_t(buf, 4, flags); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POWER_STATUS, buf, MAVLINK_MSG_ID_POWER_STATUS_MIN_LEN, MAVLINK_MSG_ID_POWER_STATUS_LEN, MAVLINK_MSG_ID_POWER_STATUS_CRC); -#else - mavlink_power_status_t *packet = (mavlink_power_status_t *)msgbuf; - packet->Vcc = Vcc; - packet->Vservo = Vservo; - packet->flags = flags; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POWER_STATUS, (const char *)packet, MAVLINK_MSG_ID_POWER_STATUS_MIN_LEN, MAVLINK_MSG_ID_POWER_STATUS_LEN, MAVLINK_MSG_ID_POWER_STATUS_CRC); -#endif -} -#endif - -#endif - -// MESSAGE POWER_STATUS UNPACKING - - -/** - * @brief Get field Vcc from power_status message - * - * @return [mV] 5V rail voltage. - */ -static inline uint16_t mavlink_msg_power_status_get_Vcc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 0); -} - -/** - * @brief Get field Vservo from power_status message - * - * @return [mV] Servo rail voltage. - */ -static inline uint16_t mavlink_msg_power_status_get_Vservo(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 2); -} - -/** - * @brief Get field flags from power_status message - * - * @return Bitmap of power supply status flags. - */ -static inline uint16_t mavlink_msg_power_status_get_flags(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 4); -} - -/** - * @brief Decode a power_status message into a struct - * - * @param msg The message to decode - * @param power_status C-struct to decode the message contents into - */ -static inline void mavlink_msg_power_status_decode(const mavlink_message_t* msg, mavlink_power_status_t* power_status) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - power_status->Vcc = mavlink_msg_power_status_get_Vcc(msg); - power_status->Vservo = mavlink_msg_power_status_get_Vservo(msg); - power_status->flags = mavlink_msg_power_status_get_flags(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_POWER_STATUS_LEN? msg->len : MAVLINK_MSG_ID_POWER_STATUS_LEN; - memset(power_status, 0, MAVLINK_MSG_ID_POWER_STATUS_LEN); - memcpy(power_status, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_radio_status.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_radio_status.h deleted file mode 100644 index baadd0b1..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_radio_status.h +++ /dev/null @@ -1,363 +0,0 @@ -#pragma once -// MESSAGE RADIO_STATUS PACKING - -#define MAVLINK_MSG_ID_RADIO_STATUS 109 - - -typedef struct __mavlink_radio_status_t { - uint16_t rxerrors; /*< Count of radio packet receive errors (since boot).*/ - uint16_t fixed; /*< Count of error corrected radio packets (since boot).*/ - uint8_t rssi; /*< Local (message sender) received signal strength indication in device-dependent units/scale. Values: [0-254], UINT8_MAX: invalid/unknown.*/ - uint8_t remrssi; /*< Remote (message receiver) signal strength indication in device-dependent units/scale. Values: [0-254], UINT8_MAX: invalid/unknown.*/ - uint8_t txbuf; /*< [%] Remaining free transmitter buffer space.*/ - uint8_t noise; /*< Local background noise level. These are device dependent RSSI values (scale as approx 2x dB on SiK radios). Values: [0-254], UINT8_MAX: invalid/unknown.*/ - uint8_t remnoise; /*< Remote background noise level. These are device dependent RSSI values (scale as approx 2x dB on SiK radios). Values: [0-254], UINT8_MAX: invalid/unknown.*/ -} mavlink_radio_status_t; - -#define MAVLINK_MSG_ID_RADIO_STATUS_LEN 9 -#define MAVLINK_MSG_ID_RADIO_STATUS_MIN_LEN 9 -#define MAVLINK_MSG_ID_109_LEN 9 -#define MAVLINK_MSG_ID_109_MIN_LEN 9 - -#define MAVLINK_MSG_ID_RADIO_STATUS_CRC 185 -#define MAVLINK_MSG_ID_109_CRC 185 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_RADIO_STATUS { \ - 109, \ - "RADIO_STATUS", \ - 7, \ - { { "rssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_radio_status_t, rssi) }, \ - { "remrssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_radio_status_t, remrssi) }, \ - { "txbuf", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_radio_status_t, txbuf) }, \ - { "noise", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_radio_status_t, noise) }, \ - { "remnoise", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_radio_status_t, remnoise) }, \ - { "rxerrors", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_radio_status_t, rxerrors) }, \ - { "fixed", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_radio_status_t, fixed) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_RADIO_STATUS { \ - "RADIO_STATUS", \ - 7, \ - { { "rssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_radio_status_t, rssi) }, \ - { "remrssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_radio_status_t, remrssi) }, \ - { "txbuf", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_radio_status_t, txbuf) }, \ - { "noise", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_radio_status_t, noise) }, \ - { "remnoise", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_radio_status_t, remnoise) }, \ - { "rxerrors", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_radio_status_t, rxerrors) }, \ - { "fixed", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_radio_status_t, fixed) }, \ - } \ -} -#endif - -/** - * @brief Pack a radio_status message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param rssi Local (message sender) received signal strength indication in device-dependent units/scale. Values: [0-254], UINT8_MAX: invalid/unknown. - * @param remrssi Remote (message receiver) signal strength indication in device-dependent units/scale. Values: [0-254], UINT8_MAX: invalid/unknown. - * @param txbuf [%] Remaining free transmitter buffer space. - * @param noise Local background noise level. These are device dependent RSSI values (scale as approx 2x dB on SiK radios). Values: [0-254], UINT8_MAX: invalid/unknown. - * @param remnoise Remote background noise level. These are device dependent RSSI values (scale as approx 2x dB on SiK radios). Values: [0-254], UINT8_MAX: invalid/unknown. - * @param rxerrors Count of radio packet receive errors (since boot). - * @param fixed Count of error corrected radio packets (since boot). - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_radio_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t rssi, uint8_t remrssi, uint8_t txbuf, uint8_t noise, uint8_t remnoise, uint16_t rxerrors, uint16_t fixed) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_RADIO_STATUS_LEN]; - _mav_put_uint16_t(buf, 0, rxerrors); - _mav_put_uint16_t(buf, 2, fixed); - _mav_put_uint8_t(buf, 4, rssi); - _mav_put_uint8_t(buf, 5, remrssi); - _mav_put_uint8_t(buf, 6, txbuf); - _mav_put_uint8_t(buf, 7, noise); - _mav_put_uint8_t(buf, 8, remnoise); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RADIO_STATUS_LEN); -#else - mavlink_radio_status_t packet; - packet.rxerrors = rxerrors; - packet.fixed = fixed; - packet.rssi = rssi; - packet.remrssi = remrssi; - packet.txbuf = txbuf; - packet.noise = noise; - packet.remnoise = remnoise; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RADIO_STATUS_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_RADIO_STATUS; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RADIO_STATUS_MIN_LEN, MAVLINK_MSG_ID_RADIO_STATUS_LEN, MAVLINK_MSG_ID_RADIO_STATUS_CRC); -} - -/** - * @brief Pack a radio_status message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param rssi Local (message sender) received signal strength indication in device-dependent units/scale. Values: [0-254], UINT8_MAX: invalid/unknown. - * @param remrssi Remote (message receiver) signal strength indication in device-dependent units/scale. Values: [0-254], UINT8_MAX: invalid/unknown. - * @param txbuf [%] Remaining free transmitter buffer space. - * @param noise Local background noise level. These are device dependent RSSI values (scale as approx 2x dB on SiK radios). Values: [0-254], UINT8_MAX: invalid/unknown. - * @param remnoise Remote background noise level. These are device dependent RSSI values (scale as approx 2x dB on SiK radios). Values: [0-254], UINT8_MAX: invalid/unknown. - * @param rxerrors Count of radio packet receive errors (since boot). - * @param fixed Count of error corrected radio packets (since boot). - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_radio_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t rssi,uint8_t remrssi,uint8_t txbuf,uint8_t noise,uint8_t remnoise,uint16_t rxerrors,uint16_t fixed) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_RADIO_STATUS_LEN]; - _mav_put_uint16_t(buf, 0, rxerrors); - _mav_put_uint16_t(buf, 2, fixed); - _mav_put_uint8_t(buf, 4, rssi); - _mav_put_uint8_t(buf, 5, remrssi); - _mav_put_uint8_t(buf, 6, txbuf); - _mav_put_uint8_t(buf, 7, noise); - _mav_put_uint8_t(buf, 8, remnoise); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RADIO_STATUS_LEN); -#else - mavlink_radio_status_t packet; - packet.rxerrors = rxerrors; - packet.fixed = fixed; - packet.rssi = rssi; - packet.remrssi = remrssi; - packet.txbuf = txbuf; - packet.noise = noise; - packet.remnoise = remnoise; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RADIO_STATUS_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_RADIO_STATUS; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RADIO_STATUS_MIN_LEN, MAVLINK_MSG_ID_RADIO_STATUS_LEN, MAVLINK_MSG_ID_RADIO_STATUS_CRC); -} - -/** - * @brief Encode a radio_status struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param radio_status C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_radio_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_radio_status_t* radio_status) -{ - return mavlink_msg_radio_status_pack(system_id, component_id, msg, radio_status->rssi, radio_status->remrssi, radio_status->txbuf, radio_status->noise, radio_status->remnoise, radio_status->rxerrors, radio_status->fixed); -} - -/** - * @brief Encode a radio_status struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param radio_status C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_radio_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_radio_status_t* radio_status) -{ - return mavlink_msg_radio_status_pack_chan(system_id, component_id, chan, msg, radio_status->rssi, radio_status->remrssi, radio_status->txbuf, radio_status->noise, radio_status->remnoise, radio_status->rxerrors, radio_status->fixed); -} - -/** - * @brief Send a radio_status message - * @param chan MAVLink channel to send the message - * - * @param rssi Local (message sender) received signal strength indication in device-dependent units/scale. Values: [0-254], UINT8_MAX: invalid/unknown. - * @param remrssi Remote (message receiver) signal strength indication in device-dependent units/scale. Values: [0-254], UINT8_MAX: invalid/unknown. - * @param txbuf [%] Remaining free transmitter buffer space. - * @param noise Local background noise level. These are device dependent RSSI values (scale as approx 2x dB on SiK radios). Values: [0-254], UINT8_MAX: invalid/unknown. - * @param remnoise Remote background noise level. These are device dependent RSSI values (scale as approx 2x dB on SiK radios). Values: [0-254], UINT8_MAX: invalid/unknown. - * @param rxerrors Count of radio packet receive errors (since boot). - * @param fixed Count of error corrected radio packets (since boot). - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_radio_status_send(mavlink_channel_t chan, uint8_t rssi, uint8_t remrssi, uint8_t txbuf, uint8_t noise, uint8_t remnoise, uint16_t rxerrors, uint16_t fixed) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_RADIO_STATUS_LEN]; - _mav_put_uint16_t(buf, 0, rxerrors); - _mav_put_uint16_t(buf, 2, fixed); - _mav_put_uint8_t(buf, 4, rssi); - _mav_put_uint8_t(buf, 5, remrssi); - _mav_put_uint8_t(buf, 6, txbuf); - _mav_put_uint8_t(buf, 7, noise); - _mav_put_uint8_t(buf, 8, remnoise); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RADIO_STATUS, buf, MAVLINK_MSG_ID_RADIO_STATUS_MIN_LEN, MAVLINK_MSG_ID_RADIO_STATUS_LEN, MAVLINK_MSG_ID_RADIO_STATUS_CRC); -#else - mavlink_radio_status_t packet; - packet.rxerrors = rxerrors; - packet.fixed = fixed; - packet.rssi = rssi; - packet.remrssi = remrssi; - packet.txbuf = txbuf; - packet.noise = noise; - packet.remnoise = remnoise; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RADIO_STATUS, (const char *)&packet, MAVLINK_MSG_ID_RADIO_STATUS_MIN_LEN, MAVLINK_MSG_ID_RADIO_STATUS_LEN, MAVLINK_MSG_ID_RADIO_STATUS_CRC); -#endif -} - -/** - * @brief Send a radio_status message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_radio_status_send_struct(mavlink_channel_t chan, const mavlink_radio_status_t* radio_status) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_radio_status_send(chan, radio_status->rssi, radio_status->remrssi, radio_status->txbuf, radio_status->noise, radio_status->remnoise, radio_status->rxerrors, radio_status->fixed); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RADIO_STATUS, (const char *)radio_status, MAVLINK_MSG_ID_RADIO_STATUS_MIN_LEN, MAVLINK_MSG_ID_RADIO_STATUS_LEN, MAVLINK_MSG_ID_RADIO_STATUS_CRC); -#endif -} - -#if MAVLINK_MSG_ID_RADIO_STATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_radio_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t rssi, uint8_t remrssi, uint8_t txbuf, uint8_t noise, uint8_t remnoise, uint16_t rxerrors, uint16_t fixed) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint16_t(buf, 0, rxerrors); - _mav_put_uint16_t(buf, 2, fixed); - _mav_put_uint8_t(buf, 4, rssi); - _mav_put_uint8_t(buf, 5, remrssi); - _mav_put_uint8_t(buf, 6, txbuf); - _mav_put_uint8_t(buf, 7, noise); - _mav_put_uint8_t(buf, 8, remnoise); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RADIO_STATUS, buf, MAVLINK_MSG_ID_RADIO_STATUS_MIN_LEN, MAVLINK_MSG_ID_RADIO_STATUS_LEN, MAVLINK_MSG_ID_RADIO_STATUS_CRC); -#else - mavlink_radio_status_t *packet = (mavlink_radio_status_t *)msgbuf; - packet->rxerrors = rxerrors; - packet->fixed = fixed; - packet->rssi = rssi; - packet->remrssi = remrssi; - packet->txbuf = txbuf; - packet->noise = noise; - packet->remnoise = remnoise; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RADIO_STATUS, (const char *)packet, MAVLINK_MSG_ID_RADIO_STATUS_MIN_LEN, MAVLINK_MSG_ID_RADIO_STATUS_LEN, MAVLINK_MSG_ID_RADIO_STATUS_CRC); -#endif -} -#endif - -#endif - -// MESSAGE RADIO_STATUS UNPACKING - - -/** - * @brief Get field rssi from radio_status message - * - * @return Local (message sender) received signal strength indication in device-dependent units/scale. Values: [0-254], UINT8_MAX: invalid/unknown. - */ -static inline uint8_t mavlink_msg_radio_status_get_rssi(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 4); -} - -/** - * @brief Get field remrssi from radio_status message - * - * @return Remote (message receiver) signal strength indication in device-dependent units/scale. Values: [0-254], UINT8_MAX: invalid/unknown. - */ -static inline uint8_t mavlink_msg_radio_status_get_remrssi(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 5); -} - -/** - * @brief Get field txbuf from radio_status message - * - * @return [%] Remaining free transmitter buffer space. - */ -static inline uint8_t mavlink_msg_radio_status_get_txbuf(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 6); -} - -/** - * @brief Get field noise from radio_status message - * - * @return Local background noise level. These are device dependent RSSI values (scale as approx 2x dB on SiK radios). Values: [0-254], UINT8_MAX: invalid/unknown. - */ -static inline uint8_t mavlink_msg_radio_status_get_noise(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 7); -} - -/** - * @brief Get field remnoise from radio_status message - * - * @return Remote background noise level. These are device dependent RSSI values (scale as approx 2x dB on SiK radios). Values: [0-254], UINT8_MAX: invalid/unknown. - */ -static inline uint8_t mavlink_msg_radio_status_get_remnoise(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 8); -} - -/** - * @brief Get field rxerrors from radio_status message - * - * @return Count of radio packet receive errors (since boot). - */ -static inline uint16_t mavlink_msg_radio_status_get_rxerrors(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 0); -} - -/** - * @brief Get field fixed from radio_status message - * - * @return Count of error corrected radio packets (since boot). - */ -static inline uint16_t mavlink_msg_radio_status_get_fixed(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 2); -} - -/** - * @brief Decode a radio_status message into a struct - * - * @param msg The message to decode - * @param radio_status C-struct to decode the message contents into - */ -static inline void mavlink_msg_radio_status_decode(const mavlink_message_t* msg, mavlink_radio_status_t* radio_status) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - radio_status->rxerrors = mavlink_msg_radio_status_get_rxerrors(msg); - radio_status->fixed = mavlink_msg_radio_status_get_fixed(msg); - radio_status->rssi = mavlink_msg_radio_status_get_rssi(msg); - radio_status->remrssi = mavlink_msg_radio_status_get_remrssi(msg); - radio_status->txbuf = mavlink_msg_radio_status_get_txbuf(msg); - radio_status->noise = mavlink_msg_radio_status_get_noise(msg); - radio_status->remnoise = mavlink_msg_radio_status_get_remnoise(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_RADIO_STATUS_LEN? msg->len : MAVLINK_MSG_ID_RADIO_STATUS_LEN; - memset(radio_status, 0, MAVLINK_MSG_ID_RADIO_STATUS_LEN); - memcpy(radio_status, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_raw_imu.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_raw_imu.h deleted file mode 100644 index f80b8012..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_raw_imu.h +++ /dev/null @@ -1,488 +0,0 @@ -#pragma once -// MESSAGE RAW_IMU PACKING - -#define MAVLINK_MSG_ID_RAW_IMU 27 - -MAVPACKED( -typedef struct __mavlink_raw_imu_t { - uint64_t time_usec; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/ - int16_t xacc; /*< X acceleration (raw)*/ - int16_t yacc; /*< Y acceleration (raw)*/ - int16_t zacc; /*< Z acceleration (raw)*/ - int16_t xgyro; /*< Angular speed around X axis (raw)*/ - int16_t ygyro; /*< Angular speed around Y axis (raw)*/ - int16_t zgyro; /*< Angular speed around Z axis (raw)*/ - int16_t xmag; /*< X Magnetic field (raw)*/ - int16_t ymag; /*< Y Magnetic field (raw)*/ - int16_t zmag; /*< Z Magnetic field (raw)*/ - uint8_t id; /*< Id. Ids are numbered from 0 and map to IMUs numbered from 1 (e.g. IMU1 will have a message with id=0)*/ - int16_t temperature; /*< [cdegC] Temperature, 0: IMU does not provide temperature values. If the IMU is at 0C it must send 1 (0.01C).*/ -}) mavlink_raw_imu_t; - -#define MAVLINK_MSG_ID_RAW_IMU_LEN 29 -#define MAVLINK_MSG_ID_RAW_IMU_MIN_LEN 26 -#define MAVLINK_MSG_ID_27_LEN 29 -#define MAVLINK_MSG_ID_27_MIN_LEN 26 - -#define MAVLINK_MSG_ID_RAW_IMU_CRC 144 -#define MAVLINK_MSG_ID_27_CRC 144 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_RAW_IMU { \ - 27, \ - "RAW_IMU", \ - 12, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_raw_imu_t, time_usec) }, \ - { "xacc", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_raw_imu_t, xacc) }, \ - { "yacc", NULL, MAVLINK_TYPE_INT16_T, 0, 10, offsetof(mavlink_raw_imu_t, yacc) }, \ - { "zacc", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_raw_imu_t, zacc) }, \ - { "xgyro", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_raw_imu_t, xgyro) }, \ - { "ygyro", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_raw_imu_t, ygyro) }, \ - { "zgyro", NULL, MAVLINK_TYPE_INT16_T, 0, 18, offsetof(mavlink_raw_imu_t, zgyro) }, \ - { "xmag", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_raw_imu_t, xmag) }, \ - { "ymag", NULL, MAVLINK_TYPE_INT16_T, 0, 22, offsetof(mavlink_raw_imu_t, ymag) }, \ - { "zmag", NULL, MAVLINK_TYPE_INT16_T, 0, 24, offsetof(mavlink_raw_imu_t, zmag) }, \ - { "id", NULL, MAVLINK_TYPE_UINT8_T, 0, 26, offsetof(mavlink_raw_imu_t, id) }, \ - { "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 27, offsetof(mavlink_raw_imu_t, temperature) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_RAW_IMU { \ - "RAW_IMU", \ - 12, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_raw_imu_t, time_usec) }, \ - { "xacc", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_raw_imu_t, xacc) }, \ - { "yacc", NULL, MAVLINK_TYPE_INT16_T, 0, 10, offsetof(mavlink_raw_imu_t, yacc) }, \ - { "zacc", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_raw_imu_t, zacc) }, \ - { "xgyro", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_raw_imu_t, xgyro) }, \ - { "ygyro", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_raw_imu_t, ygyro) }, \ - { "zgyro", NULL, MAVLINK_TYPE_INT16_T, 0, 18, offsetof(mavlink_raw_imu_t, zgyro) }, \ - { "xmag", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_raw_imu_t, xmag) }, \ - { "ymag", NULL, MAVLINK_TYPE_INT16_T, 0, 22, offsetof(mavlink_raw_imu_t, ymag) }, \ - { "zmag", NULL, MAVLINK_TYPE_INT16_T, 0, 24, offsetof(mavlink_raw_imu_t, zmag) }, \ - { "id", NULL, MAVLINK_TYPE_UINT8_T, 0, 26, offsetof(mavlink_raw_imu_t, id) }, \ - { "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 27, offsetof(mavlink_raw_imu_t, temperature) }, \ - } \ -} -#endif - -/** - * @brief Pack a raw_imu message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @param xacc X acceleration (raw) - * @param yacc Y acceleration (raw) - * @param zacc Z acceleration (raw) - * @param xgyro Angular speed around X axis (raw) - * @param ygyro Angular speed around Y axis (raw) - * @param zgyro Angular speed around Z axis (raw) - * @param xmag X Magnetic field (raw) - * @param ymag Y Magnetic field (raw) - * @param zmag Z Magnetic field (raw) - * @param id Id. Ids are numbered from 0 and map to IMUs numbered from 1 (e.g. IMU1 will have a message with id=0) - * @param temperature [cdegC] Temperature, 0: IMU does not provide temperature values. If the IMU is at 0C it must send 1 (0.01C). - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_raw_imu_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint64_t time_usec, int16_t xacc, int16_t yacc, int16_t zacc, int16_t xgyro, int16_t ygyro, int16_t zgyro, int16_t xmag, int16_t ymag, int16_t zmag, uint8_t id, int16_t temperature) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_RAW_IMU_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_int16_t(buf, 8, xacc); - _mav_put_int16_t(buf, 10, yacc); - _mav_put_int16_t(buf, 12, zacc); - _mav_put_int16_t(buf, 14, xgyro); - _mav_put_int16_t(buf, 16, ygyro); - _mav_put_int16_t(buf, 18, zgyro); - _mav_put_int16_t(buf, 20, xmag); - _mav_put_int16_t(buf, 22, ymag); - _mav_put_int16_t(buf, 24, zmag); - _mav_put_uint8_t(buf, 26, id); - _mav_put_int16_t(buf, 27, temperature); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RAW_IMU_LEN); -#else - mavlink_raw_imu_t packet; - packet.time_usec = time_usec; - packet.xacc = xacc; - packet.yacc = yacc; - packet.zacc = zacc; - packet.xgyro = xgyro; - packet.ygyro = ygyro; - packet.zgyro = zgyro; - packet.xmag = xmag; - packet.ymag = ymag; - packet.zmag = zmag; - packet.id = id; - packet.temperature = temperature; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RAW_IMU_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_RAW_IMU; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RAW_IMU_MIN_LEN, MAVLINK_MSG_ID_RAW_IMU_LEN, MAVLINK_MSG_ID_RAW_IMU_CRC); -} - -/** - * @brief Pack a raw_imu message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @param xacc X acceleration (raw) - * @param yacc Y acceleration (raw) - * @param zacc Z acceleration (raw) - * @param xgyro Angular speed around X axis (raw) - * @param ygyro Angular speed around Y axis (raw) - * @param zgyro Angular speed around Z axis (raw) - * @param xmag X Magnetic field (raw) - * @param ymag Y Magnetic field (raw) - * @param zmag Z Magnetic field (raw) - * @param id Id. Ids are numbered from 0 and map to IMUs numbered from 1 (e.g. IMU1 will have a message with id=0) - * @param temperature [cdegC] Temperature, 0: IMU does not provide temperature values. If the IMU is at 0C it must send 1 (0.01C). - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_raw_imu_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint64_t time_usec,int16_t xacc,int16_t yacc,int16_t zacc,int16_t xgyro,int16_t ygyro,int16_t zgyro,int16_t xmag,int16_t ymag,int16_t zmag,uint8_t id,int16_t temperature) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_RAW_IMU_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_int16_t(buf, 8, xacc); - _mav_put_int16_t(buf, 10, yacc); - _mav_put_int16_t(buf, 12, zacc); - _mav_put_int16_t(buf, 14, xgyro); - _mav_put_int16_t(buf, 16, ygyro); - _mav_put_int16_t(buf, 18, zgyro); - _mav_put_int16_t(buf, 20, xmag); - _mav_put_int16_t(buf, 22, ymag); - _mav_put_int16_t(buf, 24, zmag); - _mav_put_uint8_t(buf, 26, id); - _mav_put_int16_t(buf, 27, temperature); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RAW_IMU_LEN); -#else - mavlink_raw_imu_t packet; - packet.time_usec = time_usec; - packet.xacc = xacc; - packet.yacc = yacc; - packet.zacc = zacc; - packet.xgyro = xgyro; - packet.ygyro = ygyro; - packet.zgyro = zgyro; - packet.xmag = xmag; - packet.ymag = ymag; - packet.zmag = zmag; - packet.id = id; - packet.temperature = temperature; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RAW_IMU_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_RAW_IMU; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RAW_IMU_MIN_LEN, MAVLINK_MSG_ID_RAW_IMU_LEN, MAVLINK_MSG_ID_RAW_IMU_CRC); -} - -/** - * @brief Encode a raw_imu struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param raw_imu C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_raw_imu_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_raw_imu_t* raw_imu) -{ - return mavlink_msg_raw_imu_pack(system_id, component_id, msg, raw_imu->time_usec, raw_imu->xacc, raw_imu->yacc, raw_imu->zacc, raw_imu->xgyro, raw_imu->ygyro, raw_imu->zgyro, raw_imu->xmag, raw_imu->ymag, raw_imu->zmag, raw_imu->id, raw_imu->temperature); -} - -/** - * @brief Encode a raw_imu struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param raw_imu C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_raw_imu_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_raw_imu_t* raw_imu) -{ - return mavlink_msg_raw_imu_pack_chan(system_id, component_id, chan, msg, raw_imu->time_usec, raw_imu->xacc, raw_imu->yacc, raw_imu->zacc, raw_imu->xgyro, raw_imu->ygyro, raw_imu->zgyro, raw_imu->xmag, raw_imu->ymag, raw_imu->zmag, raw_imu->id, raw_imu->temperature); -} - -/** - * @brief Send a raw_imu message - * @param chan MAVLink channel to send the message - * - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @param xacc X acceleration (raw) - * @param yacc Y acceleration (raw) - * @param zacc Z acceleration (raw) - * @param xgyro Angular speed around X axis (raw) - * @param ygyro Angular speed around Y axis (raw) - * @param zgyro Angular speed around Z axis (raw) - * @param xmag X Magnetic field (raw) - * @param ymag Y Magnetic field (raw) - * @param zmag Z Magnetic field (raw) - * @param id Id. Ids are numbered from 0 and map to IMUs numbered from 1 (e.g. IMU1 will have a message with id=0) - * @param temperature [cdegC] Temperature, 0: IMU does not provide temperature values. If the IMU is at 0C it must send 1 (0.01C). - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_raw_imu_send(mavlink_channel_t chan, uint64_t time_usec, int16_t xacc, int16_t yacc, int16_t zacc, int16_t xgyro, int16_t ygyro, int16_t zgyro, int16_t xmag, int16_t ymag, int16_t zmag, uint8_t id, int16_t temperature) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_RAW_IMU_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_int16_t(buf, 8, xacc); - _mav_put_int16_t(buf, 10, yacc); - _mav_put_int16_t(buf, 12, zacc); - _mav_put_int16_t(buf, 14, xgyro); - _mav_put_int16_t(buf, 16, ygyro); - _mav_put_int16_t(buf, 18, zgyro); - _mav_put_int16_t(buf, 20, xmag); - _mav_put_int16_t(buf, 22, ymag); - _mav_put_int16_t(buf, 24, zmag); - _mav_put_uint8_t(buf, 26, id); - _mav_put_int16_t(buf, 27, temperature); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_IMU, buf, MAVLINK_MSG_ID_RAW_IMU_MIN_LEN, MAVLINK_MSG_ID_RAW_IMU_LEN, MAVLINK_MSG_ID_RAW_IMU_CRC); -#else - mavlink_raw_imu_t packet; - packet.time_usec = time_usec; - packet.xacc = xacc; - packet.yacc = yacc; - packet.zacc = zacc; - packet.xgyro = xgyro; - packet.ygyro = ygyro; - packet.zgyro = zgyro; - packet.xmag = xmag; - packet.ymag = ymag; - packet.zmag = zmag; - packet.id = id; - packet.temperature = temperature; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_IMU, (const char *)&packet, MAVLINK_MSG_ID_RAW_IMU_MIN_LEN, MAVLINK_MSG_ID_RAW_IMU_LEN, MAVLINK_MSG_ID_RAW_IMU_CRC); -#endif -} - -/** - * @brief Send a raw_imu message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_raw_imu_send_struct(mavlink_channel_t chan, const mavlink_raw_imu_t* raw_imu) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_raw_imu_send(chan, raw_imu->time_usec, raw_imu->xacc, raw_imu->yacc, raw_imu->zacc, raw_imu->xgyro, raw_imu->ygyro, raw_imu->zgyro, raw_imu->xmag, raw_imu->ymag, raw_imu->zmag, raw_imu->id, raw_imu->temperature); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_IMU, (const char *)raw_imu, MAVLINK_MSG_ID_RAW_IMU_MIN_LEN, MAVLINK_MSG_ID_RAW_IMU_LEN, MAVLINK_MSG_ID_RAW_IMU_CRC); -#endif -} - -#if MAVLINK_MSG_ID_RAW_IMU_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_raw_imu_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, int16_t xacc, int16_t yacc, int16_t zacc, int16_t xgyro, int16_t ygyro, int16_t zgyro, int16_t xmag, int16_t ymag, int16_t zmag, uint8_t id, int16_t temperature) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_int16_t(buf, 8, xacc); - _mav_put_int16_t(buf, 10, yacc); - _mav_put_int16_t(buf, 12, zacc); - _mav_put_int16_t(buf, 14, xgyro); - _mav_put_int16_t(buf, 16, ygyro); - _mav_put_int16_t(buf, 18, zgyro); - _mav_put_int16_t(buf, 20, xmag); - _mav_put_int16_t(buf, 22, ymag); - _mav_put_int16_t(buf, 24, zmag); - _mav_put_uint8_t(buf, 26, id); - _mav_put_int16_t(buf, 27, temperature); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_IMU, buf, MAVLINK_MSG_ID_RAW_IMU_MIN_LEN, MAVLINK_MSG_ID_RAW_IMU_LEN, MAVLINK_MSG_ID_RAW_IMU_CRC); -#else - mavlink_raw_imu_t *packet = (mavlink_raw_imu_t *)msgbuf; - packet->time_usec = time_usec; - packet->xacc = xacc; - packet->yacc = yacc; - packet->zacc = zacc; - packet->xgyro = xgyro; - packet->ygyro = ygyro; - packet->zgyro = zgyro; - packet->xmag = xmag; - packet->ymag = ymag; - packet->zmag = zmag; - packet->id = id; - packet->temperature = temperature; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_IMU, (const char *)packet, MAVLINK_MSG_ID_RAW_IMU_MIN_LEN, MAVLINK_MSG_ID_RAW_IMU_LEN, MAVLINK_MSG_ID_RAW_IMU_CRC); -#endif -} -#endif - -#endif - -// MESSAGE RAW_IMU UNPACKING - - -/** - * @brief Get field time_usec from raw_imu message - * - * @return [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - */ -static inline uint64_t mavlink_msg_raw_imu_get_time_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field xacc from raw_imu message - * - * @return X acceleration (raw) - */ -static inline int16_t mavlink_msg_raw_imu_get_xacc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 8); -} - -/** - * @brief Get field yacc from raw_imu message - * - * @return Y acceleration (raw) - */ -static inline int16_t mavlink_msg_raw_imu_get_yacc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 10); -} - -/** - * @brief Get field zacc from raw_imu message - * - * @return Z acceleration (raw) - */ -static inline int16_t mavlink_msg_raw_imu_get_zacc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 12); -} - -/** - * @brief Get field xgyro from raw_imu message - * - * @return Angular speed around X axis (raw) - */ -static inline int16_t mavlink_msg_raw_imu_get_xgyro(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 14); -} - -/** - * @brief Get field ygyro from raw_imu message - * - * @return Angular speed around Y axis (raw) - */ -static inline int16_t mavlink_msg_raw_imu_get_ygyro(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 16); -} - -/** - * @brief Get field zgyro from raw_imu message - * - * @return Angular speed around Z axis (raw) - */ -static inline int16_t mavlink_msg_raw_imu_get_zgyro(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 18); -} - -/** - * @brief Get field xmag from raw_imu message - * - * @return X Magnetic field (raw) - */ -static inline int16_t mavlink_msg_raw_imu_get_xmag(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 20); -} - -/** - * @brief Get field ymag from raw_imu message - * - * @return Y Magnetic field (raw) - */ -static inline int16_t mavlink_msg_raw_imu_get_ymag(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 22); -} - -/** - * @brief Get field zmag from raw_imu message - * - * @return Z Magnetic field (raw) - */ -static inline int16_t mavlink_msg_raw_imu_get_zmag(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 24); -} - -/** - * @brief Get field id from raw_imu message - * - * @return Id. Ids are numbered from 0 and map to IMUs numbered from 1 (e.g. IMU1 will have a message with id=0) - */ -static inline uint8_t mavlink_msg_raw_imu_get_id(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 26); -} - -/** - * @brief Get field temperature from raw_imu message - * - * @return [cdegC] Temperature, 0: IMU does not provide temperature values. If the IMU is at 0C it must send 1 (0.01C). - */ -static inline int16_t mavlink_msg_raw_imu_get_temperature(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 27); -} - -/** - * @brief Decode a raw_imu message into a struct - * - * @param msg The message to decode - * @param raw_imu C-struct to decode the message contents into - */ -static inline void mavlink_msg_raw_imu_decode(const mavlink_message_t* msg, mavlink_raw_imu_t* raw_imu) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - raw_imu->time_usec = mavlink_msg_raw_imu_get_time_usec(msg); - raw_imu->xacc = mavlink_msg_raw_imu_get_xacc(msg); - raw_imu->yacc = mavlink_msg_raw_imu_get_yacc(msg); - raw_imu->zacc = mavlink_msg_raw_imu_get_zacc(msg); - raw_imu->xgyro = mavlink_msg_raw_imu_get_xgyro(msg); - raw_imu->ygyro = mavlink_msg_raw_imu_get_ygyro(msg); - raw_imu->zgyro = mavlink_msg_raw_imu_get_zgyro(msg); - raw_imu->xmag = mavlink_msg_raw_imu_get_xmag(msg); - raw_imu->ymag = mavlink_msg_raw_imu_get_ymag(msg); - raw_imu->zmag = mavlink_msg_raw_imu_get_zmag(msg); - raw_imu->id = mavlink_msg_raw_imu_get_id(msg); - raw_imu->temperature = mavlink_msg_raw_imu_get_temperature(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_RAW_IMU_LEN? msg->len : MAVLINK_MSG_ID_RAW_IMU_LEN; - memset(raw_imu, 0, MAVLINK_MSG_ID_RAW_IMU_LEN); - memcpy(raw_imu, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_raw_pressure.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_raw_pressure.h deleted file mode 100644 index b0f49dc9..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_raw_pressure.h +++ /dev/null @@ -1,313 +0,0 @@ -#pragma once -// MESSAGE RAW_PRESSURE PACKING - -#define MAVLINK_MSG_ID_RAW_PRESSURE 28 - - -typedef struct __mavlink_raw_pressure_t { - uint64_t time_usec; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/ - int16_t press_abs; /*< Absolute pressure (raw)*/ - int16_t press_diff1; /*< Differential pressure 1 (raw, 0 if nonexistent)*/ - int16_t press_diff2; /*< Differential pressure 2 (raw, 0 if nonexistent)*/ - int16_t temperature; /*< Raw Temperature measurement (raw)*/ -} mavlink_raw_pressure_t; - -#define MAVLINK_MSG_ID_RAW_PRESSURE_LEN 16 -#define MAVLINK_MSG_ID_RAW_PRESSURE_MIN_LEN 16 -#define MAVLINK_MSG_ID_28_LEN 16 -#define MAVLINK_MSG_ID_28_MIN_LEN 16 - -#define MAVLINK_MSG_ID_RAW_PRESSURE_CRC 67 -#define MAVLINK_MSG_ID_28_CRC 67 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_RAW_PRESSURE { \ - 28, \ - "RAW_PRESSURE", \ - 5, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_raw_pressure_t, time_usec) }, \ - { "press_abs", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_raw_pressure_t, press_abs) }, \ - { "press_diff1", NULL, MAVLINK_TYPE_INT16_T, 0, 10, offsetof(mavlink_raw_pressure_t, press_diff1) }, \ - { "press_diff2", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_raw_pressure_t, press_diff2) }, \ - { "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_raw_pressure_t, temperature) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_RAW_PRESSURE { \ - "RAW_PRESSURE", \ - 5, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_raw_pressure_t, time_usec) }, \ - { "press_abs", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_raw_pressure_t, press_abs) }, \ - { "press_diff1", NULL, MAVLINK_TYPE_INT16_T, 0, 10, offsetof(mavlink_raw_pressure_t, press_diff1) }, \ - { "press_diff2", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_raw_pressure_t, press_diff2) }, \ - { "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_raw_pressure_t, temperature) }, \ - } \ -} -#endif - -/** - * @brief Pack a raw_pressure message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @param press_abs Absolute pressure (raw) - * @param press_diff1 Differential pressure 1 (raw, 0 if nonexistent) - * @param press_diff2 Differential pressure 2 (raw, 0 if nonexistent) - * @param temperature Raw Temperature measurement (raw) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_raw_pressure_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint64_t time_usec, int16_t press_abs, int16_t press_diff1, int16_t press_diff2, int16_t temperature) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_RAW_PRESSURE_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_int16_t(buf, 8, press_abs); - _mav_put_int16_t(buf, 10, press_diff1); - _mav_put_int16_t(buf, 12, press_diff2); - _mav_put_int16_t(buf, 14, temperature); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RAW_PRESSURE_LEN); -#else - mavlink_raw_pressure_t packet; - packet.time_usec = time_usec; - packet.press_abs = press_abs; - packet.press_diff1 = press_diff1; - packet.press_diff2 = press_diff2; - packet.temperature = temperature; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RAW_PRESSURE_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_RAW_PRESSURE; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RAW_PRESSURE_MIN_LEN, MAVLINK_MSG_ID_RAW_PRESSURE_LEN, MAVLINK_MSG_ID_RAW_PRESSURE_CRC); -} - -/** - * @brief Pack a raw_pressure message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @param press_abs Absolute pressure (raw) - * @param press_diff1 Differential pressure 1 (raw, 0 if nonexistent) - * @param press_diff2 Differential pressure 2 (raw, 0 if nonexistent) - * @param temperature Raw Temperature measurement (raw) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_raw_pressure_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint64_t time_usec,int16_t press_abs,int16_t press_diff1,int16_t press_diff2,int16_t temperature) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_RAW_PRESSURE_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_int16_t(buf, 8, press_abs); - _mav_put_int16_t(buf, 10, press_diff1); - _mav_put_int16_t(buf, 12, press_diff2); - _mav_put_int16_t(buf, 14, temperature); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RAW_PRESSURE_LEN); -#else - mavlink_raw_pressure_t packet; - packet.time_usec = time_usec; - packet.press_abs = press_abs; - packet.press_diff1 = press_diff1; - packet.press_diff2 = press_diff2; - packet.temperature = temperature; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RAW_PRESSURE_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_RAW_PRESSURE; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RAW_PRESSURE_MIN_LEN, MAVLINK_MSG_ID_RAW_PRESSURE_LEN, MAVLINK_MSG_ID_RAW_PRESSURE_CRC); -} - -/** - * @brief Encode a raw_pressure struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param raw_pressure C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_raw_pressure_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_raw_pressure_t* raw_pressure) -{ - return mavlink_msg_raw_pressure_pack(system_id, component_id, msg, raw_pressure->time_usec, raw_pressure->press_abs, raw_pressure->press_diff1, raw_pressure->press_diff2, raw_pressure->temperature); -} - -/** - * @brief Encode a raw_pressure struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param raw_pressure C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_raw_pressure_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_raw_pressure_t* raw_pressure) -{ - return mavlink_msg_raw_pressure_pack_chan(system_id, component_id, chan, msg, raw_pressure->time_usec, raw_pressure->press_abs, raw_pressure->press_diff1, raw_pressure->press_diff2, raw_pressure->temperature); -} - -/** - * @brief Send a raw_pressure message - * @param chan MAVLink channel to send the message - * - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @param press_abs Absolute pressure (raw) - * @param press_diff1 Differential pressure 1 (raw, 0 if nonexistent) - * @param press_diff2 Differential pressure 2 (raw, 0 if nonexistent) - * @param temperature Raw Temperature measurement (raw) - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_raw_pressure_send(mavlink_channel_t chan, uint64_t time_usec, int16_t press_abs, int16_t press_diff1, int16_t press_diff2, int16_t temperature) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_RAW_PRESSURE_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_int16_t(buf, 8, press_abs); - _mav_put_int16_t(buf, 10, press_diff1); - _mav_put_int16_t(buf, 12, press_diff2); - _mav_put_int16_t(buf, 14, temperature); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_PRESSURE, buf, MAVLINK_MSG_ID_RAW_PRESSURE_MIN_LEN, MAVLINK_MSG_ID_RAW_PRESSURE_LEN, MAVLINK_MSG_ID_RAW_PRESSURE_CRC); -#else - mavlink_raw_pressure_t packet; - packet.time_usec = time_usec; - packet.press_abs = press_abs; - packet.press_diff1 = press_diff1; - packet.press_diff2 = press_diff2; - packet.temperature = temperature; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_PRESSURE, (const char *)&packet, MAVLINK_MSG_ID_RAW_PRESSURE_MIN_LEN, MAVLINK_MSG_ID_RAW_PRESSURE_LEN, MAVLINK_MSG_ID_RAW_PRESSURE_CRC); -#endif -} - -/** - * @brief Send a raw_pressure message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_raw_pressure_send_struct(mavlink_channel_t chan, const mavlink_raw_pressure_t* raw_pressure) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_raw_pressure_send(chan, raw_pressure->time_usec, raw_pressure->press_abs, raw_pressure->press_diff1, raw_pressure->press_diff2, raw_pressure->temperature); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_PRESSURE, (const char *)raw_pressure, MAVLINK_MSG_ID_RAW_PRESSURE_MIN_LEN, MAVLINK_MSG_ID_RAW_PRESSURE_LEN, MAVLINK_MSG_ID_RAW_PRESSURE_CRC); -#endif -} - -#if MAVLINK_MSG_ID_RAW_PRESSURE_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_raw_pressure_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, int16_t press_abs, int16_t press_diff1, int16_t press_diff2, int16_t temperature) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_int16_t(buf, 8, press_abs); - _mav_put_int16_t(buf, 10, press_diff1); - _mav_put_int16_t(buf, 12, press_diff2); - _mav_put_int16_t(buf, 14, temperature); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_PRESSURE, buf, MAVLINK_MSG_ID_RAW_PRESSURE_MIN_LEN, MAVLINK_MSG_ID_RAW_PRESSURE_LEN, MAVLINK_MSG_ID_RAW_PRESSURE_CRC); -#else - mavlink_raw_pressure_t *packet = (mavlink_raw_pressure_t *)msgbuf; - packet->time_usec = time_usec; - packet->press_abs = press_abs; - packet->press_diff1 = press_diff1; - packet->press_diff2 = press_diff2; - packet->temperature = temperature; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_PRESSURE, (const char *)packet, MAVLINK_MSG_ID_RAW_PRESSURE_MIN_LEN, MAVLINK_MSG_ID_RAW_PRESSURE_LEN, MAVLINK_MSG_ID_RAW_PRESSURE_CRC); -#endif -} -#endif - -#endif - -// MESSAGE RAW_PRESSURE UNPACKING - - -/** - * @brief Get field time_usec from raw_pressure message - * - * @return [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - */ -static inline uint64_t mavlink_msg_raw_pressure_get_time_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field press_abs from raw_pressure message - * - * @return Absolute pressure (raw) - */ -static inline int16_t mavlink_msg_raw_pressure_get_press_abs(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 8); -} - -/** - * @brief Get field press_diff1 from raw_pressure message - * - * @return Differential pressure 1 (raw, 0 if nonexistent) - */ -static inline int16_t mavlink_msg_raw_pressure_get_press_diff1(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 10); -} - -/** - * @brief Get field press_diff2 from raw_pressure message - * - * @return Differential pressure 2 (raw, 0 if nonexistent) - */ -static inline int16_t mavlink_msg_raw_pressure_get_press_diff2(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 12); -} - -/** - * @brief Get field temperature from raw_pressure message - * - * @return Raw Temperature measurement (raw) - */ -static inline int16_t mavlink_msg_raw_pressure_get_temperature(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 14); -} - -/** - * @brief Decode a raw_pressure message into a struct - * - * @param msg The message to decode - * @param raw_pressure C-struct to decode the message contents into - */ -static inline void mavlink_msg_raw_pressure_decode(const mavlink_message_t* msg, mavlink_raw_pressure_t* raw_pressure) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - raw_pressure->time_usec = mavlink_msg_raw_pressure_get_time_usec(msg); - raw_pressure->press_abs = mavlink_msg_raw_pressure_get_press_abs(msg); - raw_pressure->press_diff1 = mavlink_msg_raw_pressure_get_press_diff1(msg); - raw_pressure->press_diff2 = mavlink_msg_raw_pressure_get_press_diff2(msg); - raw_pressure->temperature = mavlink_msg_raw_pressure_get_temperature(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_RAW_PRESSURE_LEN? msg->len : MAVLINK_MSG_ID_RAW_PRESSURE_LEN; - memset(raw_pressure, 0, MAVLINK_MSG_ID_RAW_PRESSURE_LEN); - memcpy(raw_pressure, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_raw_rpm.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_raw_rpm.h deleted file mode 100644 index e34cdbf7..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_raw_rpm.h +++ /dev/null @@ -1,238 +0,0 @@ -#pragma once -// MESSAGE RAW_RPM PACKING - -#define MAVLINK_MSG_ID_RAW_RPM 339 - - -typedef struct __mavlink_raw_rpm_t { - float frequency; /*< [rpm] Indicated rate*/ - uint8_t index; /*< Index of this RPM sensor (0-indexed)*/ -} mavlink_raw_rpm_t; - -#define MAVLINK_MSG_ID_RAW_RPM_LEN 5 -#define MAVLINK_MSG_ID_RAW_RPM_MIN_LEN 5 -#define MAVLINK_MSG_ID_339_LEN 5 -#define MAVLINK_MSG_ID_339_MIN_LEN 5 - -#define MAVLINK_MSG_ID_RAW_RPM_CRC 199 -#define MAVLINK_MSG_ID_339_CRC 199 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_RAW_RPM { \ - 339, \ - "RAW_RPM", \ - 2, \ - { { "index", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_raw_rpm_t, index) }, \ - { "frequency", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_raw_rpm_t, frequency) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_RAW_RPM { \ - "RAW_RPM", \ - 2, \ - { { "index", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_raw_rpm_t, index) }, \ - { "frequency", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_raw_rpm_t, frequency) }, \ - } \ -} -#endif - -/** - * @brief Pack a raw_rpm message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param index Index of this RPM sensor (0-indexed) - * @param frequency [rpm] Indicated rate - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_raw_rpm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t index, float frequency) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_RAW_RPM_LEN]; - _mav_put_float(buf, 0, frequency); - _mav_put_uint8_t(buf, 4, index); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RAW_RPM_LEN); -#else - mavlink_raw_rpm_t packet; - packet.frequency = frequency; - packet.index = index; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RAW_RPM_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_RAW_RPM; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RAW_RPM_MIN_LEN, MAVLINK_MSG_ID_RAW_RPM_LEN, MAVLINK_MSG_ID_RAW_RPM_CRC); -} - -/** - * @brief Pack a raw_rpm message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param index Index of this RPM sensor (0-indexed) - * @param frequency [rpm] Indicated rate - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_raw_rpm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t index,float frequency) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_RAW_RPM_LEN]; - _mav_put_float(buf, 0, frequency); - _mav_put_uint8_t(buf, 4, index); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RAW_RPM_LEN); -#else - mavlink_raw_rpm_t packet; - packet.frequency = frequency; - packet.index = index; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RAW_RPM_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_RAW_RPM; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RAW_RPM_MIN_LEN, MAVLINK_MSG_ID_RAW_RPM_LEN, MAVLINK_MSG_ID_RAW_RPM_CRC); -} - -/** - * @brief Encode a raw_rpm struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param raw_rpm C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_raw_rpm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_raw_rpm_t* raw_rpm) -{ - return mavlink_msg_raw_rpm_pack(system_id, component_id, msg, raw_rpm->index, raw_rpm->frequency); -} - -/** - * @brief Encode a raw_rpm struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param raw_rpm C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_raw_rpm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_raw_rpm_t* raw_rpm) -{ - return mavlink_msg_raw_rpm_pack_chan(system_id, component_id, chan, msg, raw_rpm->index, raw_rpm->frequency); -} - -/** - * @brief Send a raw_rpm message - * @param chan MAVLink channel to send the message - * - * @param index Index of this RPM sensor (0-indexed) - * @param frequency [rpm] Indicated rate - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_raw_rpm_send(mavlink_channel_t chan, uint8_t index, float frequency) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_RAW_RPM_LEN]; - _mav_put_float(buf, 0, frequency); - _mav_put_uint8_t(buf, 4, index); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_RPM, buf, MAVLINK_MSG_ID_RAW_RPM_MIN_LEN, MAVLINK_MSG_ID_RAW_RPM_LEN, MAVLINK_MSG_ID_RAW_RPM_CRC); -#else - mavlink_raw_rpm_t packet; - packet.frequency = frequency; - packet.index = index; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_RPM, (const char *)&packet, MAVLINK_MSG_ID_RAW_RPM_MIN_LEN, MAVLINK_MSG_ID_RAW_RPM_LEN, MAVLINK_MSG_ID_RAW_RPM_CRC); -#endif -} - -/** - * @brief Send a raw_rpm message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_raw_rpm_send_struct(mavlink_channel_t chan, const mavlink_raw_rpm_t* raw_rpm) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_raw_rpm_send(chan, raw_rpm->index, raw_rpm->frequency); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_RPM, (const char *)raw_rpm, MAVLINK_MSG_ID_RAW_RPM_MIN_LEN, MAVLINK_MSG_ID_RAW_RPM_LEN, MAVLINK_MSG_ID_RAW_RPM_CRC); -#endif -} - -#if MAVLINK_MSG_ID_RAW_RPM_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_raw_rpm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t index, float frequency) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_float(buf, 0, frequency); - _mav_put_uint8_t(buf, 4, index); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_RPM, buf, MAVLINK_MSG_ID_RAW_RPM_MIN_LEN, MAVLINK_MSG_ID_RAW_RPM_LEN, MAVLINK_MSG_ID_RAW_RPM_CRC); -#else - mavlink_raw_rpm_t *packet = (mavlink_raw_rpm_t *)msgbuf; - packet->frequency = frequency; - packet->index = index; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_RPM, (const char *)packet, MAVLINK_MSG_ID_RAW_RPM_MIN_LEN, MAVLINK_MSG_ID_RAW_RPM_LEN, MAVLINK_MSG_ID_RAW_RPM_CRC); -#endif -} -#endif - -#endif - -// MESSAGE RAW_RPM UNPACKING - - -/** - * @brief Get field index from raw_rpm message - * - * @return Index of this RPM sensor (0-indexed) - */ -static inline uint8_t mavlink_msg_raw_rpm_get_index(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 4); -} - -/** - * @brief Get field frequency from raw_rpm message - * - * @return [rpm] Indicated rate - */ -static inline float mavlink_msg_raw_rpm_get_frequency(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 0); -} - -/** - * @brief Decode a raw_rpm message into a struct - * - * @param msg The message to decode - * @param raw_rpm C-struct to decode the message contents into - */ -static inline void mavlink_msg_raw_rpm_decode(const mavlink_message_t* msg, mavlink_raw_rpm_t* raw_rpm) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - raw_rpm->frequency = mavlink_msg_raw_rpm_get_frequency(msg); - raw_rpm->index = mavlink_msg_raw_rpm_get_index(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_RAW_RPM_LEN? msg->len : MAVLINK_MSG_ID_RAW_RPM_LEN; - memset(raw_rpm, 0, MAVLINK_MSG_ID_RAW_RPM_LEN); - memcpy(raw_rpm, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_rc_channels.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_rc_channels.h deleted file mode 100644 index 721bc65e..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_rc_channels.h +++ /dev/null @@ -1,713 +0,0 @@ -#pragma once -// MESSAGE RC_CHANNELS PACKING - -#define MAVLINK_MSG_ID_RC_CHANNELS 65 - - -typedef struct __mavlink_rc_channels_t { - uint32_t time_boot_ms; /*< [ms] Timestamp (time since system boot).*/ - uint16_t chan1_raw; /*< [us] RC channel 1 value.*/ - uint16_t chan2_raw; /*< [us] RC channel 2 value.*/ - uint16_t chan3_raw; /*< [us] RC channel 3 value.*/ - uint16_t chan4_raw; /*< [us] RC channel 4 value.*/ - uint16_t chan5_raw; /*< [us] RC channel 5 value.*/ - uint16_t chan6_raw; /*< [us] RC channel 6 value.*/ - uint16_t chan7_raw; /*< [us] RC channel 7 value.*/ - uint16_t chan8_raw; /*< [us] RC channel 8 value.*/ - uint16_t chan9_raw; /*< [us] RC channel 9 value.*/ - uint16_t chan10_raw; /*< [us] RC channel 10 value.*/ - uint16_t chan11_raw; /*< [us] RC channel 11 value.*/ - uint16_t chan12_raw; /*< [us] RC channel 12 value.*/ - uint16_t chan13_raw; /*< [us] RC channel 13 value.*/ - uint16_t chan14_raw; /*< [us] RC channel 14 value.*/ - uint16_t chan15_raw; /*< [us] RC channel 15 value.*/ - uint16_t chan16_raw; /*< [us] RC channel 16 value.*/ - uint16_t chan17_raw; /*< [us] RC channel 17 value.*/ - uint16_t chan18_raw; /*< [us] RC channel 18 value.*/ - uint8_t chancount; /*< Total number of RC channels being received. This can be larger than 18, indicating that more channels are available but not given in this message. This value should be 0 when no RC channels are available.*/ - uint8_t rssi; /*< Receive signal strength indicator in device-dependent units/scale. Values: [0-254], UINT8_MAX: invalid/unknown.*/ -} mavlink_rc_channels_t; - -#define MAVLINK_MSG_ID_RC_CHANNELS_LEN 42 -#define MAVLINK_MSG_ID_RC_CHANNELS_MIN_LEN 42 -#define MAVLINK_MSG_ID_65_LEN 42 -#define MAVLINK_MSG_ID_65_MIN_LEN 42 - -#define MAVLINK_MSG_ID_RC_CHANNELS_CRC 118 -#define MAVLINK_MSG_ID_65_CRC 118 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_RC_CHANNELS { \ - 65, \ - "RC_CHANNELS", \ - 21, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_rc_channels_t, time_boot_ms) }, \ - { "chancount", NULL, MAVLINK_TYPE_UINT8_T, 0, 40, offsetof(mavlink_rc_channels_t, chancount) }, \ - { "chan1_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_rc_channels_t, chan1_raw) }, \ - { "chan2_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_rc_channels_t, chan2_raw) }, \ - { "chan3_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_rc_channels_t, chan3_raw) }, \ - { "chan4_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_rc_channels_t, chan4_raw) }, \ - { "chan5_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_rc_channels_t, chan5_raw) }, \ - { "chan6_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_rc_channels_t, chan6_raw) }, \ - { "chan7_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_rc_channels_t, chan7_raw) }, \ - { "chan8_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_rc_channels_t, chan8_raw) }, \ - { "chan9_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_rc_channels_t, chan9_raw) }, \ - { "chan10_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_rc_channels_t, chan10_raw) }, \ - { "chan11_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_rc_channels_t, chan11_raw) }, \ - { "chan12_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_rc_channels_t, chan12_raw) }, \ - { "chan13_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_rc_channels_t, chan13_raw) }, \ - { "chan14_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 30, offsetof(mavlink_rc_channels_t, chan14_raw) }, \ - { "chan15_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 32, offsetof(mavlink_rc_channels_t, chan15_raw) }, \ - { "chan16_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 34, offsetof(mavlink_rc_channels_t, chan16_raw) }, \ - { "chan17_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 36, offsetof(mavlink_rc_channels_t, chan17_raw) }, \ - { "chan18_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 38, offsetof(mavlink_rc_channels_t, chan18_raw) }, \ - { "rssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 41, offsetof(mavlink_rc_channels_t, rssi) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_RC_CHANNELS { \ - "RC_CHANNELS", \ - 21, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_rc_channels_t, time_boot_ms) }, \ - { "chancount", NULL, MAVLINK_TYPE_UINT8_T, 0, 40, offsetof(mavlink_rc_channels_t, chancount) }, \ - { "chan1_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_rc_channels_t, chan1_raw) }, \ - { "chan2_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_rc_channels_t, chan2_raw) }, \ - { "chan3_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_rc_channels_t, chan3_raw) }, \ - { "chan4_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_rc_channels_t, chan4_raw) }, \ - { "chan5_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_rc_channels_t, chan5_raw) }, \ - { "chan6_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_rc_channels_t, chan6_raw) }, \ - { "chan7_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_rc_channels_t, chan7_raw) }, \ - { "chan8_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_rc_channels_t, chan8_raw) }, \ - { "chan9_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_rc_channels_t, chan9_raw) }, \ - { "chan10_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_rc_channels_t, chan10_raw) }, \ - { "chan11_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_rc_channels_t, chan11_raw) }, \ - { "chan12_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_rc_channels_t, chan12_raw) }, \ - { "chan13_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_rc_channels_t, chan13_raw) }, \ - { "chan14_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 30, offsetof(mavlink_rc_channels_t, chan14_raw) }, \ - { "chan15_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 32, offsetof(mavlink_rc_channels_t, chan15_raw) }, \ - { "chan16_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 34, offsetof(mavlink_rc_channels_t, chan16_raw) }, \ - { "chan17_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 36, offsetof(mavlink_rc_channels_t, chan17_raw) }, \ - { "chan18_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 38, offsetof(mavlink_rc_channels_t, chan18_raw) }, \ - { "rssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 41, offsetof(mavlink_rc_channels_t, rssi) }, \ - } \ -} -#endif - -/** - * @brief Pack a rc_channels message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param time_boot_ms [ms] Timestamp (time since system boot). - * @param chancount Total number of RC channels being received. This can be larger than 18, indicating that more channels are available but not given in this message. This value should be 0 when no RC channels are available. - * @param chan1_raw [us] RC channel 1 value. - * @param chan2_raw [us] RC channel 2 value. - * @param chan3_raw [us] RC channel 3 value. - * @param chan4_raw [us] RC channel 4 value. - * @param chan5_raw [us] RC channel 5 value. - * @param chan6_raw [us] RC channel 6 value. - * @param chan7_raw [us] RC channel 7 value. - * @param chan8_raw [us] RC channel 8 value. - * @param chan9_raw [us] RC channel 9 value. - * @param chan10_raw [us] RC channel 10 value. - * @param chan11_raw [us] RC channel 11 value. - * @param chan12_raw [us] RC channel 12 value. - * @param chan13_raw [us] RC channel 13 value. - * @param chan14_raw [us] RC channel 14 value. - * @param chan15_raw [us] RC channel 15 value. - * @param chan16_raw [us] RC channel 16 value. - * @param chan17_raw [us] RC channel 17 value. - * @param chan18_raw [us] RC channel 18 value. - * @param rssi Receive signal strength indicator in device-dependent units/scale. Values: [0-254], UINT8_MAX: invalid/unknown. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_rc_channels_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint32_t time_boot_ms, uint8_t chancount, uint16_t chan1_raw, uint16_t chan2_raw, uint16_t chan3_raw, uint16_t chan4_raw, uint16_t chan5_raw, uint16_t chan6_raw, uint16_t chan7_raw, uint16_t chan8_raw, uint16_t chan9_raw, uint16_t chan10_raw, uint16_t chan11_raw, uint16_t chan12_raw, uint16_t chan13_raw, uint16_t chan14_raw, uint16_t chan15_raw, uint16_t chan16_raw, uint16_t chan17_raw, uint16_t chan18_raw, uint8_t rssi) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_RC_CHANNELS_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_uint16_t(buf, 4, chan1_raw); - _mav_put_uint16_t(buf, 6, chan2_raw); - _mav_put_uint16_t(buf, 8, chan3_raw); - _mav_put_uint16_t(buf, 10, chan4_raw); - _mav_put_uint16_t(buf, 12, chan5_raw); - _mav_put_uint16_t(buf, 14, chan6_raw); - _mav_put_uint16_t(buf, 16, chan7_raw); - _mav_put_uint16_t(buf, 18, chan8_raw); - _mav_put_uint16_t(buf, 20, chan9_raw); - _mav_put_uint16_t(buf, 22, chan10_raw); - _mav_put_uint16_t(buf, 24, chan11_raw); - _mav_put_uint16_t(buf, 26, chan12_raw); - _mav_put_uint16_t(buf, 28, chan13_raw); - _mav_put_uint16_t(buf, 30, chan14_raw); - _mav_put_uint16_t(buf, 32, chan15_raw); - _mav_put_uint16_t(buf, 34, chan16_raw); - _mav_put_uint16_t(buf, 36, chan17_raw); - _mav_put_uint16_t(buf, 38, chan18_raw); - _mav_put_uint8_t(buf, 40, chancount); - _mav_put_uint8_t(buf, 41, rssi); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RC_CHANNELS_LEN); -#else - mavlink_rc_channels_t packet; - packet.time_boot_ms = time_boot_ms; - packet.chan1_raw = chan1_raw; - packet.chan2_raw = chan2_raw; - packet.chan3_raw = chan3_raw; - packet.chan4_raw = chan4_raw; - packet.chan5_raw = chan5_raw; - packet.chan6_raw = chan6_raw; - packet.chan7_raw = chan7_raw; - packet.chan8_raw = chan8_raw; - packet.chan9_raw = chan9_raw; - packet.chan10_raw = chan10_raw; - packet.chan11_raw = chan11_raw; - packet.chan12_raw = chan12_raw; - packet.chan13_raw = chan13_raw; - packet.chan14_raw = chan14_raw; - packet.chan15_raw = chan15_raw; - packet.chan16_raw = chan16_raw; - packet.chan17_raw = chan17_raw; - packet.chan18_raw = chan18_raw; - packet.chancount = chancount; - packet.rssi = rssi; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RC_CHANNELS_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_RC_CHANNELS; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RC_CHANNELS_MIN_LEN, MAVLINK_MSG_ID_RC_CHANNELS_LEN, MAVLINK_MSG_ID_RC_CHANNELS_CRC); -} - -/** - * @brief Pack a rc_channels message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_boot_ms [ms] Timestamp (time since system boot). - * @param chancount Total number of RC channels being received. This can be larger than 18, indicating that more channels are available but not given in this message. This value should be 0 when no RC channels are available. - * @param chan1_raw [us] RC channel 1 value. - * @param chan2_raw [us] RC channel 2 value. - * @param chan3_raw [us] RC channel 3 value. - * @param chan4_raw [us] RC channel 4 value. - * @param chan5_raw [us] RC channel 5 value. - * @param chan6_raw [us] RC channel 6 value. - * @param chan7_raw [us] RC channel 7 value. - * @param chan8_raw [us] RC channel 8 value. - * @param chan9_raw [us] RC channel 9 value. - * @param chan10_raw [us] RC channel 10 value. - * @param chan11_raw [us] RC channel 11 value. - * @param chan12_raw [us] RC channel 12 value. - * @param chan13_raw [us] RC channel 13 value. - * @param chan14_raw [us] RC channel 14 value. - * @param chan15_raw [us] RC channel 15 value. - * @param chan16_raw [us] RC channel 16 value. - * @param chan17_raw [us] RC channel 17 value. - * @param chan18_raw [us] RC channel 18 value. - * @param rssi Receive signal strength indicator in device-dependent units/scale. Values: [0-254], UINT8_MAX: invalid/unknown. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_rc_channels_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint32_t time_boot_ms,uint8_t chancount,uint16_t chan1_raw,uint16_t chan2_raw,uint16_t chan3_raw,uint16_t chan4_raw,uint16_t chan5_raw,uint16_t chan6_raw,uint16_t chan7_raw,uint16_t chan8_raw,uint16_t chan9_raw,uint16_t chan10_raw,uint16_t chan11_raw,uint16_t chan12_raw,uint16_t chan13_raw,uint16_t chan14_raw,uint16_t chan15_raw,uint16_t chan16_raw,uint16_t chan17_raw,uint16_t chan18_raw,uint8_t rssi) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_RC_CHANNELS_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_uint16_t(buf, 4, chan1_raw); - _mav_put_uint16_t(buf, 6, chan2_raw); - _mav_put_uint16_t(buf, 8, chan3_raw); - _mav_put_uint16_t(buf, 10, chan4_raw); - _mav_put_uint16_t(buf, 12, chan5_raw); - _mav_put_uint16_t(buf, 14, chan6_raw); - _mav_put_uint16_t(buf, 16, chan7_raw); - _mav_put_uint16_t(buf, 18, chan8_raw); - _mav_put_uint16_t(buf, 20, chan9_raw); - _mav_put_uint16_t(buf, 22, chan10_raw); - _mav_put_uint16_t(buf, 24, chan11_raw); - _mav_put_uint16_t(buf, 26, chan12_raw); - _mav_put_uint16_t(buf, 28, chan13_raw); - _mav_put_uint16_t(buf, 30, chan14_raw); - _mav_put_uint16_t(buf, 32, chan15_raw); - _mav_put_uint16_t(buf, 34, chan16_raw); - _mav_put_uint16_t(buf, 36, chan17_raw); - _mav_put_uint16_t(buf, 38, chan18_raw); - _mav_put_uint8_t(buf, 40, chancount); - _mav_put_uint8_t(buf, 41, rssi); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RC_CHANNELS_LEN); -#else - mavlink_rc_channels_t packet; - packet.time_boot_ms = time_boot_ms; - packet.chan1_raw = chan1_raw; - packet.chan2_raw = chan2_raw; - packet.chan3_raw = chan3_raw; - packet.chan4_raw = chan4_raw; - packet.chan5_raw = chan5_raw; - packet.chan6_raw = chan6_raw; - packet.chan7_raw = chan7_raw; - packet.chan8_raw = chan8_raw; - packet.chan9_raw = chan9_raw; - packet.chan10_raw = chan10_raw; - packet.chan11_raw = chan11_raw; - packet.chan12_raw = chan12_raw; - packet.chan13_raw = chan13_raw; - packet.chan14_raw = chan14_raw; - packet.chan15_raw = chan15_raw; - packet.chan16_raw = chan16_raw; - packet.chan17_raw = chan17_raw; - packet.chan18_raw = chan18_raw; - packet.chancount = chancount; - packet.rssi = rssi; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RC_CHANNELS_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_RC_CHANNELS; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RC_CHANNELS_MIN_LEN, MAVLINK_MSG_ID_RC_CHANNELS_LEN, MAVLINK_MSG_ID_RC_CHANNELS_CRC); -} - -/** - * @brief Encode a rc_channels struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param rc_channels C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_rc_channels_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_rc_channels_t* rc_channels) -{ - return mavlink_msg_rc_channels_pack(system_id, component_id, msg, rc_channels->time_boot_ms, rc_channels->chancount, rc_channels->chan1_raw, rc_channels->chan2_raw, rc_channels->chan3_raw, rc_channels->chan4_raw, rc_channels->chan5_raw, rc_channels->chan6_raw, rc_channels->chan7_raw, rc_channels->chan8_raw, rc_channels->chan9_raw, rc_channels->chan10_raw, rc_channels->chan11_raw, rc_channels->chan12_raw, rc_channels->chan13_raw, rc_channels->chan14_raw, rc_channels->chan15_raw, rc_channels->chan16_raw, rc_channels->chan17_raw, rc_channels->chan18_raw, rc_channels->rssi); -} - -/** - * @brief Encode a rc_channels struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param rc_channels C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_rc_channels_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_rc_channels_t* rc_channels) -{ - return mavlink_msg_rc_channels_pack_chan(system_id, component_id, chan, msg, rc_channels->time_boot_ms, rc_channels->chancount, rc_channels->chan1_raw, rc_channels->chan2_raw, rc_channels->chan3_raw, rc_channels->chan4_raw, rc_channels->chan5_raw, rc_channels->chan6_raw, rc_channels->chan7_raw, rc_channels->chan8_raw, rc_channels->chan9_raw, rc_channels->chan10_raw, rc_channels->chan11_raw, rc_channels->chan12_raw, rc_channels->chan13_raw, rc_channels->chan14_raw, rc_channels->chan15_raw, rc_channels->chan16_raw, rc_channels->chan17_raw, rc_channels->chan18_raw, rc_channels->rssi); -} - -/** - * @brief Send a rc_channels message - * @param chan MAVLink channel to send the message - * - * @param time_boot_ms [ms] Timestamp (time since system boot). - * @param chancount Total number of RC channels being received. This can be larger than 18, indicating that more channels are available but not given in this message. This value should be 0 when no RC channels are available. - * @param chan1_raw [us] RC channel 1 value. - * @param chan2_raw [us] RC channel 2 value. - * @param chan3_raw [us] RC channel 3 value. - * @param chan4_raw [us] RC channel 4 value. - * @param chan5_raw [us] RC channel 5 value. - * @param chan6_raw [us] RC channel 6 value. - * @param chan7_raw [us] RC channel 7 value. - * @param chan8_raw [us] RC channel 8 value. - * @param chan9_raw [us] RC channel 9 value. - * @param chan10_raw [us] RC channel 10 value. - * @param chan11_raw [us] RC channel 11 value. - * @param chan12_raw [us] RC channel 12 value. - * @param chan13_raw [us] RC channel 13 value. - * @param chan14_raw [us] RC channel 14 value. - * @param chan15_raw [us] RC channel 15 value. - * @param chan16_raw [us] RC channel 16 value. - * @param chan17_raw [us] RC channel 17 value. - * @param chan18_raw [us] RC channel 18 value. - * @param rssi Receive signal strength indicator in device-dependent units/scale. Values: [0-254], UINT8_MAX: invalid/unknown. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_rc_channels_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t chancount, uint16_t chan1_raw, uint16_t chan2_raw, uint16_t chan3_raw, uint16_t chan4_raw, uint16_t chan5_raw, uint16_t chan6_raw, uint16_t chan7_raw, uint16_t chan8_raw, uint16_t chan9_raw, uint16_t chan10_raw, uint16_t chan11_raw, uint16_t chan12_raw, uint16_t chan13_raw, uint16_t chan14_raw, uint16_t chan15_raw, uint16_t chan16_raw, uint16_t chan17_raw, uint16_t chan18_raw, uint8_t rssi) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_RC_CHANNELS_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_uint16_t(buf, 4, chan1_raw); - _mav_put_uint16_t(buf, 6, chan2_raw); - _mav_put_uint16_t(buf, 8, chan3_raw); - _mav_put_uint16_t(buf, 10, chan4_raw); - _mav_put_uint16_t(buf, 12, chan5_raw); - _mav_put_uint16_t(buf, 14, chan6_raw); - _mav_put_uint16_t(buf, 16, chan7_raw); - _mav_put_uint16_t(buf, 18, chan8_raw); - _mav_put_uint16_t(buf, 20, chan9_raw); - _mav_put_uint16_t(buf, 22, chan10_raw); - _mav_put_uint16_t(buf, 24, chan11_raw); - _mav_put_uint16_t(buf, 26, chan12_raw); - _mav_put_uint16_t(buf, 28, chan13_raw); - _mav_put_uint16_t(buf, 30, chan14_raw); - _mav_put_uint16_t(buf, 32, chan15_raw); - _mav_put_uint16_t(buf, 34, chan16_raw); - _mav_put_uint16_t(buf, 36, chan17_raw); - _mav_put_uint16_t(buf, 38, chan18_raw); - _mav_put_uint8_t(buf, 40, chancount); - _mav_put_uint8_t(buf, 41, rssi); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS, buf, MAVLINK_MSG_ID_RC_CHANNELS_MIN_LEN, MAVLINK_MSG_ID_RC_CHANNELS_LEN, MAVLINK_MSG_ID_RC_CHANNELS_CRC); -#else - mavlink_rc_channels_t packet; - packet.time_boot_ms = time_boot_ms; - packet.chan1_raw = chan1_raw; - packet.chan2_raw = chan2_raw; - packet.chan3_raw = chan3_raw; - packet.chan4_raw = chan4_raw; - packet.chan5_raw = chan5_raw; - packet.chan6_raw = chan6_raw; - packet.chan7_raw = chan7_raw; - packet.chan8_raw = chan8_raw; - packet.chan9_raw = chan9_raw; - packet.chan10_raw = chan10_raw; - packet.chan11_raw = chan11_raw; - packet.chan12_raw = chan12_raw; - packet.chan13_raw = chan13_raw; - packet.chan14_raw = chan14_raw; - packet.chan15_raw = chan15_raw; - packet.chan16_raw = chan16_raw; - packet.chan17_raw = chan17_raw; - packet.chan18_raw = chan18_raw; - packet.chancount = chancount; - packet.rssi = rssi; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS, (const char *)&packet, MAVLINK_MSG_ID_RC_CHANNELS_MIN_LEN, MAVLINK_MSG_ID_RC_CHANNELS_LEN, MAVLINK_MSG_ID_RC_CHANNELS_CRC); -#endif -} - -/** - * @brief Send a rc_channels message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_rc_channels_send_struct(mavlink_channel_t chan, const mavlink_rc_channels_t* rc_channels) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_rc_channels_send(chan, rc_channels->time_boot_ms, rc_channels->chancount, rc_channels->chan1_raw, rc_channels->chan2_raw, rc_channels->chan3_raw, rc_channels->chan4_raw, rc_channels->chan5_raw, rc_channels->chan6_raw, rc_channels->chan7_raw, rc_channels->chan8_raw, rc_channels->chan9_raw, rc_channels->chan10_raw, rc_channels->chan11_raw, rc_channels->chan12_raw, rc_channels->chan13_raw, rc_channels->chan14_raw, rc_channels->chan15_raw, rc_channels->chan16_raw, rc_channels->chan17_raw, rc_channels->chan18_raw, rc_channels->rssi); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS, (const char *)rc_channels, MAVLINK_MSG_ID_RC_CHANNELS_MIN_LEN, MAVLINK_MSG_ID_RC_CHANNELS_LEN, MAVLINK_MSG_ID_RC_CHANNELS_CRC); -#endif -} - -#if MAVLINK_MSG_ID_RC_CHANNELS_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_rc_channels_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t chancount, uint16_t chan1_raw, uint16_t chan2_raw, uint16_t chan3_raw, uint16_t chan4_raw, uint16_t chan5_raw, uint16_t chan6_raw, uint16_t chan7_raw, uint16_t chan8_raw, uint16_t chan9_raw, uint16_t chan10_raw, uint16_t chan11_raw, uint16_t chan12_raw, uint16_t chan13_raw, uint16_t chan14_raw, uint16_t chan15_raw, uint16_t chan16_raw, uint16_t chan17_raw, uint16_t chan18_raw, uint8_t rssi) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_uint16_t(buf, 4, chan1_raw); - _mav_put_uint16_t(buf, 6, chan2_raw); - _mav_put_uint16_t(buf, 8, chan3_raw); - _mav_put_uint16_t(buf, 10, chan4_raw); - _mav_put_uint16_t(buf, 12, chan5_raw); - _mav_put_uint16_t(buf, 14, chan6_raw); - _mav_put_uint16_t(buf, 16, chan7_raw); - _mav_put_uint16_t(buf, 18, chan8_raw); - _mav_put_uint16_t(buf, 20, chan9_raw); - _mav_put_uint16_t(buf, 22, chan10_raw); - _mav_put_uint16_t(buf, 24, chan11_raw); - _mav_put_uint16_t(buf, 26, chan12_raw); - _mav_put_uint16_t(buf, 28, chan13_raw); - _mav_put_uint16_t(buf, 30, chan14_raw); - _mav_put_uint16_t(buf, 32, chan15_raw); - _mav_put_uint16_t(buf, 34, chan16_raw); - _mav_put_uint16_t(buf, 36, chan17_raw); - _mav_put_uint16_t(buf, 38, chan18_raw); - _mav_put_uint8_t(buf, 40, chancount); - _mav_put_uint8_t(buf, 41, rssi); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS, buf, MAVLINK_MSG_ID_RC_CHANNELS_MIN_LEN, MAVLINK_MSG_ID_RC_CHANNELS_LEN, MAVLINK_MSG_ID_RC_CHANNELS_CRC); -#else - mavlink_rc_channels_t *packet = (mavlink_rc_channels_t *)msgbuf; - packet->time_boot_ms = time_boot_ms; - packet->chan1_raw = chan1_raw; - packet->chan2_raw = chan2_raw; - packet->chan3_raw = chan3_raw; - packet->chan4_raw = chan4_raw; - packet->chan5_raw = chan5_raw; - packet->chan6_raw = chan6_raw; - packet->chan7_raw = chan7_raw; - packet->chan8_raw = chan8_raw; - packet->chan9_raw = chan9_raw; - packet->chan10_raw = chan10_raw; - packet->chan11_raw = chan11_raw; - packet->chan12_raw = chan12_raw; - packet->chan13_raw = chan13_raw; - packet->chan14_raw = chan14_raw; - packet->chan15_raw = chan15_raw; - packet->chan16_raw = chan16_raw; - packet->chan17_raw = chan17_raw; - packet->chan18_raw = chan18_raw; - packet->chancount = chancount; - packet->rssi = rssi; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS, (const char *)packet, MAVLINK_MSG_ID_RC_CHANNELS_MIN_LEN, MAVLINK_MSG_ID_RC_CHANNELS_LEN, MAVLINK_MSG_ID_RC_CHANNELS_CRC); -#endif -} -#endif - -#endif - -// MESSAGE RC_CHANNELS UNPACKING - - -/** - * @brief Get field time_boot_ms from rc_channels message - * - * @return [ms] Timestamp (time since system boot). - */ -static inline uint32_t mavlink_msg_rc_channels_get_time_boot_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field chancount from rc_channels message - * - * @return Total number of RC channels being received. This can be larger than 18, indicating that more channels are available but not given in this message. This value should be 0 when no RC channels are available. - */ -static inline uint8_t mavlink_msg_rc_channels_get_chancount(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 40); -} - -/** - * @brief Get field chan1_raw from rc_channels message - * - * @return [us] RC channel 1 value. - */ -static inline uint16_t mavlink_msg_rc_channels_get_chan1_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 4); -} - -/** - * @brief Get field chan2_raw from rc_channels message - * - * @return [us] RC channel 2 value. - */ -static inline uint16_t mavlink_msg_rc_channels_get_chan2_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 6); -} - -/** - * @brief Get field chan3_raw from rc_channels message - * - * @return [us] RC channel 3 value. - */ -static inline uint16_t mavlink_msg_rc_channels_get_chan3_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 8); -} - -/** - * @brief Get field chan4_raw from rc_channels message - * - * @return [us] RC channel 4 value. - */ -static inline uint16_t mavlink_msg_rc_channels_get_chan4_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 10); -} - -/** - * @brief Get field chan5_raw from rc_channels message - * - * @return [us] RC channel 5 value. - */ -static inline uint16_t mavlink_msg_rc_channels_get_chan5_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 12); -} - -/** - * @brief Get field chan6_raw from rc_channels message - * - * @return [us] RC channel 6 value. - */ -static inline uint16_t mavlink_msg_rc_channels_get_chan6_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 14); -} - -/** - * @brief Get field chan7_raw from rc_channels message - * - * @return [us] RC channel 7 value. - */ -static inline uint16_t mavlink_msg_rc_channels_get_chan7_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 16); -} - -/** - * @brief Get field chan8_raw from rc_channels message - * - * @return [us] RC channel 8 value. - */ -static inline uint16_t mavlink_msg_rc_channels_get_chan8_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 18); -} - -/** - * @brief Get field chan9_raw from rc_channels message - * - * @return [us] RC channel 9 value. - */ -static inline uint16_t mavlink_msg_rc_channels_get_chan9_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 20); -} - -/** - * @brief Get field chan10_raw from rc_channels message - * - * @return [us] RC channel 10 value. - */ -static inline uint16_t mavlink_msg_rc_channels_get_chan10_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 22); -} - -/** - * @brief Get field chan11_raw from rc_channels message - * - * @return [us] RC channel 11 value. - */ -static inline uint16_t mavlink_msg_rc_channels_get_chan11_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 24); -} - -/** - * @brief Get field chan12_raw from rc_channels message - * - * @return [us] RC channel 12 value. - */ -static inline uint16_t mavlink_msg_rc_channels_get_chan12_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 26); -} - -/** - * @brief Get field chan13_raw from rc_channels message - * - * @return [us] RC channel 13 value. - */ -static inline uint16_t mavlink_msg_rc_channels_get_chan13_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 28); -} - -/** - * @brief Get field chan14_raw from rc_channels message - * - * @return [us] RC channel 14 value. - */ -static inline uint16_t mavlink_msg_rc_channels_get_chan14_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 30); -} - -/** - * @brief Get field chan15_raw from rc_channels message - * - * @return [us] RC channel 15 value. - */ -static inline uint16_t mavlink_msg_rc_channels_get_chan15_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 32); -} - -/** - * @brief Get field chan16_raw from rc_channels message - * - * @return [us] RC channel 16 value. - */ -static inline uint16_t mavlink_msg_rc_channels_get_chan16_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 34); -} - -/** - * @brief Get field chan17_raw from rc_channels message - * - * @return [us] RC channel 17 value. - */ -static inline uint16_t mavlink_msg_rc_channels_get_chan17_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 36); -} - -/** - * @brief Get field chan18_raw from rc_channels message - * - * @return [us] RC channel 18 value. - */ -static inline uint16_t mavlink_msg_rc_channels_get_chan18_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 38); -} - -/** - * @brief Get field rssi from rc_channels message - * - * @return Receive signal strength indicator in device-dependent units/scale. Values: [0-254], UINT8_MAX: invalid/unknown. - */ -static inline uint8_t mavlink_msg_rc_channels_get_rssi(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 41); -} - -/** - * @brief Decode a rc_channels message into a struct - * - * @param msg The message to decode - * @param rc_channels C-struct to decode the message contents into - */ -static inline void mavlink_msg_rc_channels_decode(const mavlink_message_t* msg, mavlink_rc_channels_t* rc_channels) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - rc_channels->time_boot_ms = mavlink_msg_rc_channels_get_time_boot_ms(msg); - rc_channels->chan1_raw = mavlink_msg_rc_channels_get_chan1_raw(msg); - rc_channels->chan2_raw = mavlink_msg_rc_channels_get_chan2_raw(msg); - rc_channels->chan3_raw = mavlink_msg_rc_channels_get_chan3_raw(msg); - rc_channels->chan4_raw = mavlink_msg_rc_channels_get_chan4_raw(msg); - rc_channels->chan5_raw = mavlink_msg_rc_channels_get_chan5_raw(msg); - rc_channels->chan6_raw = mavlink_msg_rc_channels_get_chan6_raw(msg); - rc_channels->chan7_raw = mavlink_msg_rc_channels_get_chan7_raw(msg); - rc_channels->chan8_raw = mavlink_msg_rc_channels_get_chan8_raw(msg); - rc_channels->chan9_raw = mavlink_msg_rc_channels_get_chan9_raw(msg); - rc_channels->chan10_raw = mavlink_msg_rc_channels_get_chan10_raw(msg); - rc_channels->chan11_raw = mavlink_msg_rc_channels_get_chan11_raw(msg); - rc_channels->chan12_raw = mavlink_msg_rc_channels_get_chan12_raw(msg); - rc_channels->chan13_raw = mavlink_msg_rc_channels_get_chan13_raw(msg); - rc_channels->chan14_raw = mavlink_msg_rc_channels_get_chan14_raw(msg); - rc_channels->chan15_raw = mavlink_msg_rc_channels_get_chan15_raw(msg); - rc_channels->chan16_raw = mavlink_msg_rc_channels_get_chan16_raw(msg); - rc_channels->chan17_raw = mavlink_msg_rc_channels_get_chan17_raw(msg); - rc_channels->chan18_raw = mavlink_msg_rc_channels_get_chan18_raw(msg); - rc_channels->chancount = mavlink_msg_rc_channels_get_chancount(msg); - rc_channels->rssi = mavlink_msg_rc_channels_get_rssi(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_RC_CHANNELS_LEN? msg->len : MAVLINK_MSG_ID_RC_CHANNELS_LEN; - memset(rc_channels, 0, MAVLINK_MSG_ID_RC_CHANNELS_LEN); - memcpy(rc_channels, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_rc_channels_override.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_rc_channels_override.h deleted file mode 100644 index bc973c91..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_rc_channels_override.h +++ /dev/null @@ -1,688 +0,0 @@ -#pragma once -// MESSAGE RC_CHANNELS_OVERRIDE PACKING - -#define MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE 70 - - -typedef struct __mavlink_rc_channels_override_t { - uint16_t chan1_raw; /*< [us] RC channel 1 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio.*/ - uint16_t chan2_raw; /*< [us] RC channel 2 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio.*/ - uint16_t chan3_raw; /*< [us] RC channel 3 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio.*/ - uint16_t chan4_raw; /*< [us] RC channel 4 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio.*/ - uint16_t chan5_raw; /*< [us] RC channel 5 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio.*/ - uint16_t chan6_raw; /*< [us] RC channel 6 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio.*/ - uint16_t chan7_raw; /*< [us] RC channel 7 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio.*/ - uint16_t chan8_raw; /*< [us] RC channel 8 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio.*/ - uint8_t target_system; /*< System ID*/ - uint8_t target_component; /*< Component ID*/ - uint16_t chan9_raw; /*< [us] RC channel 9 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio.*/ - uint16_t chan10_raw; /*< [us] RC channel 10 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio.*/ - uint16_t chan11_raw; /*< [us] RC channel 11 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio.*/ - uint16_t chan12_raw; /*< [us] RC channel 12 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio.*/ - uint16_t chan13_raw; /*< [us] RC channel 13 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio.*/ - uint16_t chan14_raw; /*< [us] RC channel 14 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio.*/ - uint16_t chan15_raw; /*< [us] RC channel 15 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio.*/ - uint16_t chan16_raw; /*< [us] RC channel 16 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio.*/ - uint16_t chan17_raw; /*< [us] RC channel 17 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio.*/ - uint16_t chan18_raw; /*< [us] RC channel 18 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio.*/ -} mavlink_rc_channels_override_t; - -#define MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN 38 -#define MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_MIN_LEN 18 -#define MAVLINK_MSG_ID_70_LEN 38 -#define MAVLINK_MSG_ID_70_MIN_LEN 18 - -#define MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_CRC 124 -#define MAVLINK_MSG_ID_70_CRC 124 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_RC_CHANNELS_OVERRIDE { \ - 70, \ - "RC_CHANNELS_OVERRIDE", \ - 20, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_rc_channels_override_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 17, offsetof(mavlink_rc_channels_override_t, target_component) }, \ - { "chan1_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_rc_channels_override_t, chan1_raw) }, \ - { "chan2_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_rc_channels_override_t, chan2_raw) }, \ - { "chan3_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_rc_channels_override_t, chan3_raw) }, \ - { "chan4_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_rc_channels_override_t, chan4_raw) }, \ - { "chan5_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_rc_channels_override_t, chan5_raw) }, \ - { "chan6_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_rc_channels_override_t, chan6_raw) }, \ - { "chan7_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_rc_channels_override_t, chan7_raw) }, \ - { "chan8_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_rc_channels_override_t, chan8_raw) }, \ - { "chan9_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_rc_channels_override_t, chan9_raw) }, \ - { "chan10_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_rc_channels_override_t, chan10_raw) }, \ - { "chan11_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_rc_channels_override_t, chan11_raw) }, \ - { "chan12_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_rc_channels_override_t, chan12_raw) }, \ - { "chan13_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_rc_channels_override_t, chan13_raw) }, \ - { "chan14_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_rc_channels_override_t, chan14_raw) }, \ - { "chan15_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 30, offsetof(mavlink_rc_channels_override_t, chan15_raw) }, \ - { "chan16_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 32, offsetof(mavlink_rc_channels_override_t, chan16_raw) }, \ - { "chan17_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 34, offsetof(mavlink_rc_channels_override_t, chan17_raw) }, \ - { "chan18_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 36, offsetof(mavlink_rc_channels_override_t, chan18_raw) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_RC_CHANNELS_OVERRIDE { \ - "RC_CHANNELS_OVERRIDE", \ - 20, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_rc_channels_override_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 17, offsetof(mavlink_rc_channels_override_t, target_component) }, \ - { "chan1_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_rc_channels_override_t, chan1_raw) }, \ - { "chan2_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_rc_channels_override_t, chan2_raw) }, \ - { "chan3_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_rc_channels_override_t, chan3_raw) }, \ - { "chan4_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_rc_channels_override_t, chan4_raw) }, \ - { "chan5_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_rc_channels_override_t, chan5_raw) }, \ - { "chan6_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_rc_channels_override_t, chan6_raw) }, \ - { "chan7_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_rc_channels_override_t, chan7_raw) }, \ - { "chan8_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_rc_channels_override_t, chan8_raw) }, \ - { "chan9_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_rc_channels_override_t, chan9_raw) }, \ - { "chan10_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_rc_channels_override_t, chan10_raw) }, \ - { "chan11_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_rc_channels_override_t, chan11_raw) }, \ - { "chan12_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_rc_channels_override_t, chan12_raw) }, \ - { "chan13_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_rc_channels_override_t, chan13_raw) }, \ - { "chan14_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_rc_channels_override_t, chan14_raw) }, \ - { "chan15_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 30, offsetof(mavlink_rc_channels_override_t, chan15_raw) }, \ - { "chan16_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 32, offsetof(mavlink_rc_channels_override_t, chan16_raw) }, \ - { "chan17_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 34, offsetof(mavlink_rc_channels_override_t, chan17_raw) }, \ - { "chan18_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 36, offsetof(mavlink_rc_channels_override_t, chan18_raw) }, \ - } \ -} -#endif - -/** - * @brief Pack a rc_channels_override message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID - * @param target_component Component ID - * @param chan1_raw [us] RC channel 1 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio. - * @param chan2_raw [us] RC channel 2 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio. - * @param chan3_raw [us] RC channel 3 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio. - * @param chan4_raw [us] RC channel 4 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio. - * @param chan5_raw [us] RC channel 5 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio. - * @param chan6_raw [us] RC channel 6 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio. - * @param chan7_raw [us] RC channel 7 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio. - * @param chan8_raw [us] RC channel 8 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio. - * @param chan9_raw [us] RC channel 9 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio. - * @param chan10_raw [us] RC channel 10 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio. - * @param chan11_raw [us] RC channel 11 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio. - * @param chan12_raw [us] RC channel 12 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio. - * @param chan13_raw [us] RC channel 13 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio. - * @param chan14_raw [us] RC channel 14 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio. - * @param chan15_raw [us] RC channel 15 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio. - * @param chan16_raw [us] RC channel 16 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio. - * @param chan17_raw [us] RC channel 17 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio. - * @param chan18_raw [us] RC channel 18 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_rc_channels_override_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component, uint16_t chan1_raw, uint16_t chan2_raw, uint16_t chan3_raw, uint16_t chan4_raw, uint16_t chan5_raw, uint16_t chan6_raw, uint16_t chan7_raw, uint16_t chan8_raw, uint16_t chan9_raw, uint16_t chan10_raw, uint16_t chan11_raw, uint16_t chan12_raw, uint16_t chan13_raw, uint16_t chan14_raw, uint16_t chan15_raw, uint16_t chan16_raw, uint16_t chan17_raw, uint16_t chan18_raw) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN]; - _mav_put_uint16_t(buf, 0, chan1_raw); - _mav_put_uint16_t(buf, 2, chan2_raw); - _mav_put_uint16_t(buf, 4, chan3_raw); - _mav_put_uint16_t(buf, 6, chan4_raw); - _mav_put_uint16_t(buf, 8, chan5_raw); - _mav_put_uint16_t(buf, 10, chan6_raw); - _mav_put_uint16_t(buf, 12, chan7_raw); - _mav_put_uint16_t(buf, 14, chan8_raw); - _mav_put_uint8_t(buf, 16, target_system); - _mav_put_uint8_t(buf, 17, target_component); - _mav_put_uint16_t(buf, 18, chan9_raw); - _mav_put_uint16_t(buf, 20, chan10_raw); - _mav_put_uint16_t(buf, 22, chan11_raw); - _mav_put_uint16_t(buf, 24, chan12_raw); - _mav_put_uint16_t(buf, 26, chan13_raw); - _mav_put_uint16_t(buf, 28, chan14_raw); - _mav_put_uint16_t(buf, 30, chan15_raw); - _mav_put_uint16_t(buf, 32, chan16_raw); - _mav_put_uint16_t(buf, 34, chan17_raw); - _mav_put_uint16_t(buf, 36, chan18_raw); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN); -#else - mavlink_rc_channels_override_t packet; - packet.chan1_raw = chan1_raw; - packet.chan2_raw = chan2_raw; - packet.chan3_raw = chan3_raw; - packet.chan4_raw = chan4_raw; - packet.chan5_raw = chan5_raw; - packet.chan6_raw = chan6_raw; - packet.chan7_raw = chan7_raw; - packet.chan8_raw = chan8_raw; - packet.target_system = target_system; - packet.target_component = target_component; - packet.chan9_raw = chan9_raw; - packet.chan10_raw = chan10_raw; - packet.chan11_raw = chan11_raw; - packet.chan12_raw = chan12_raw; - packet.chan13_raw = chan13_raw; - packet.chan14_raw = chan14_raw; - packet.chan15_raw = chan15_raw; - packet.chan16_raw = chan16_raw; - packet.chan17_raw = chan17_raw; - packet.chan18_raw = chan18_raw; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_MIN_LEN, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_CRC); -} - -/** - * @brief Pack a rc_channels_override message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @param chan1_raw [us] RC channel 1 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio. - * @param chan2_raw [us] RC channel 2 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio. - * @param chan3_raw [us] RC channel 3 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio. - * @param chan4_raw [us] RC channel 4 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio. - * @param chan5_raw [us] RC channel 5 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio. - * @param chan6_raw [us] RC channel 6 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio. - * @param chan7_raw [us] RC channel 7 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio. - * @param chan8_raw [us] RC channel 8 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio. - * @param chan9_raw [us] RC channel 9 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio. - * @param chan10_raw [us] RC channel 10 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio. - * @param chan11_raw [us] RC channel 11 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio. - * @param chan12_raw [us] RC channel 12 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio. - * @param chan13_raw [us] RC channel 13 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio. - * @param chan14_raw [us] RC channel 14 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio. - * @param chan15_raw [us] RC channel 15 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio. - * @param chan16_raw [us] RC channel 16 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio. - * @param chan17_raw [us] RC channel 17 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio. - * @param chan18_raw [us] RC channel 18 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_rc_channels_override_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component,uint16_t chan1_raw,uint16_t chan2_raw,uint16_t chan3_raw,uint16_t chan4_raw,uint16_t chan5_raw,uint16_t chan6_raw,uint16_t chan7_raw,uint16_t chan8_raw,uint16_t chan9_raw,uint16_t chan10_raw,uint16_t chan11_raw,uint16_t chan12_raw,uint16_t chan13_raw,uint16_t chan14_raw,uint16_t chan15_raw,uint16_t chan16_raw,uint16_t chan17_raw,uint16_t chan18_raw) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN]; - _mav_put_uint16_t(buf, 0, chan1_raw); - _mav_put_uint16_t(buf, 2, chan2_raw); - _mav_put_uint16_t(buf, 4, chan3_raw); - _mav_put_uint16_t(buf, 6, chan4_raw); - _mav_put_uint16_t(buf, 8, chan5_raw); - _mav_put_uint16_t(buf, 10, chan6_raw); - _mav_put_uint16_t(buf, 12, chan7_raw); - _mav_put_uint16_t(buf, 14, chan8_raw); - _mav_put_uint8_t(buf, 16, target_system); - _mav_put_uint8_t(buf, 17, target_component); - _mav_put_uint16_t(buf, 18, chan9_raw); - _mav_put_uint16_t(buf, 20, chan10_raw); - _mav_put_uint16_t(buf, 22, chan11_raw); - _mav_put_uint16_t(buf, 24, chan12_raw); - _mav_put_uint16_t(buf, 26, chan13_raw); - _mav_put_uint16_t(buf, 28, chan14_raw); - _mav_put_uint16_t(buf, 30, chan15_raw); - _mav_put_uint16_t(buf, 32, chan16_raw); - _mav_put_uint16_t(buf, 34, chan17_raw); - _mav_put_uint16_t(buf, 36, chan18_raw); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN); -#else - mavlink_rc_channels_override_t packet; - packet.chan1_raw = chan1_raw; - packet.chan2_raw = chan2_raw; - packet.chan3_raw = chan3_raw; - packet.chan4_raw = chan4_raw; - packet.chan5_raw = chan5_raw; - packet.chan6_raw = chan6_raw; - packet.chan7_raw = chan7_raw; - packet.chan8_raw = chan8_raw; - packet.target_system = target_system; - packet.target_component = target_component; - packet.chan9_raw = chan9_raw; - packet.chan10_raw = chan10_raw; - packet.chan11_raw = chan11_raw; - packet.chan12_raw = chan12_raw; - packet.chan13_raw = chan13_raw; - packet.chan14_raw = chan14_raw; - packet.chan15_raw = chan15_raw; - packet.chan16_raw = chan16_raw; - packet.chan17_raw = chan17_raw; - packet.chan18_raw = chan18_raw; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_MIN_LEN, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_CRC); -} - -/** - * @brief Encode a rc_channels_override struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param rc_channels_override C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_rc_channels_override_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_rc_channels_override_t* rc_channels_override) -{ - return mavlink_msg_rc_channels_override_pack(system_id, component_id, msg, rc_channels_override->target_system, rc_channels_override->target_component, rc_channels_override->chan1_raw, rc_channels_override->chan2_raw, rc_channels_override->chan3_raw, rc_channels_override->chan4_raw, rc_channels_override->chan5_raw, rc_channels_override->chan6_raw, rc_channels_override->chan7_raw, rc_channels_override->chan8_raw, rc_channels_override->chan9_raw, rc_channels_override->chan10_raw, rc_channels_override->chan11_raw, rc_channels_override->chan12_raw, rc_channels_override->chan13_raw, rc_channels_override->chan14_raw, rc_channels_override->chan15_raw, rc_channels_override->chan16_raw, rc_channels_override->chan17_raw, rc_channels_override->chan18_raw); -} - -/** - * @brief Encode a rc_channels_override struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param rc_channels_override C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_rc_channels_override_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_rc_channels_override_t* rc_channels_override) -{ - return mavlink_msg_rc_channels_override_pack_chan(system_id, component_id, chan, msg, rc_channels_override->target_system, rc_channels_override->target_component, rc_channels_override->chan1_raw, rc_channels_override->chan2_raw, rc_channels_override->chan3_raw, rc_channels_override->chan4_raw, rc_channels_override->chan5_raw, rc_channels_override->chan6_raw, rc_channels_override->chan7_raw, rc_channels_override->chan8_raw, rc_channels_override->chan9_raw, rc_channels_override->chan10_raw, rc_channels_override->chan11_raw, rc_channels_override->chan12_raw, rc_channels_override->chan13_raw, rc_channels_override->chan14_raw, rc_channels_override->chan15_raw, rc_channels_override->chan16_raw, rc_channels_override->chan17_raw, rc_channels_override->chan18_raw); -} - -/** - * @brief Send a rc_channels_override message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param target_component Component ID - * @param chan1_raw [us] RC channel 1 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio. - * @param chan2_raw [us] RC channel 2 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio. - * @param chan3_raw [us] RC channel 3 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio. - * @param chan4_raw [us] RC channel 4 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio. - * @param chan5_raw [us] RC channel 5 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio. - * @param chan6_raw [us] RC channel 6 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio. - * @param chan7_raw [us] RC channel 7 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio. - * @param chan8_raw [us] RC channel 8 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio. - * @param chan9_raw [us] RC channel 9 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio. - * @param chan10_raw [us] RC channel 10 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio. - * @param chan11_raw [us] RC channel 11 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio. - * @param chan12_raw [us] RC channel 12 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio. - * @param chan13_raw [us] RC channel 13 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio. - * @param chan14_raw [us] RC channel 14 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio. - * @param chan15_raw [us] RC channel 15 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio. - * @param chan16_raw [us] RC channel 16 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio. - * @param chan17_raw [us] RC channel 17 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio. - * @param chan18_raw [us] RC channel 18 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_rc_channels_override_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t chan1_raw, uint16_t chan2_raw, uint16_t chan3_raw, uint16_t chan4_raw, uint16_t chan5_raw, uint16_t chan6_raw, uint16_t chan7_raw, uint16_t chan8_raw, uint16_t chan9_raw, uint16_t chan10_raw, uint16_t chan11_raw, uint16_t chan12_raw, uint16_t chan13_raw, uint16_t chan14_raw, uint16_t chan15_raw, uint16_t chan16_raw, uint16_t chan17_raw, uint16_t chan18_raw) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN]; - _mav_put_uint16_t(buf, 0, chan1_raw); - _mav_put_uint16_t(buf, 2, chan2_raw); - _mav_put_uint16_t(buf, 4, chan3_raw); - _mav_put_uint16_t(buf, 6, chan4_raw); - _mav_put_uint16_t(buf, 8, chan5_raw); - _mav_put_uint16_t(buf, 10, chan6_raw); - _mav_put_uint16_t(buf, 12, chan7_raw); - _mav_put_uint16_t(buf, 14, chan8_raw); - _mav_put_uint8_t(buf, 16, target_system); - _mav_put_uint8_t(buf, 17, target_component); - _mav_put_uint16_t(buf, 18, chan9_raw); - _mav_put_uint16_t(buf, 20, chan10_raw); - _mav_put_uint16_t(buf, 22, chan11_raw); - _mav_put_uint16_t(buf, 24, chan12_raw); - _mav_put_uint16_t(buf, 26, chan13_raw); - _mav_put_uint16_t(buf, 28, chan14_raw); - _mav_put_uint16_t(buf, 30, chan15_raw); - _mav_put_uint16_t(buf, 32, chan16_raw); - _mav_put_uint16_t(buf, 34, chan17_raw); - _mav_put_uint16_t(buf, 36, chan18_raw); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE, buf, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_MIN_LEN, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_CRC); -#else - mavlink_rc_channels_override_t packet; - packet.chan1_raw = chan1_raw; - packet.chan2_raw = chan2_raw; - packet.chan3_raw = chan3_raw; - packet.chan4_raw = chan4_raw; - packet.chan5_raw = chan5_raw; - packet.chan6_raw = chan6_raw; - packet.chan7_raw = chan7_raw; - packet.chan8_raw = chan8_raw; - packet.target_system = target_system; - packet.target_component = target_component; - packet.chan9_raw = chan9_raw; - packet.chan10_raw = chan10_raw; - packet.chan11_raw = chan11_raw; - packet.chan12_raw = chan12_raw; - packet.chan13_raw = chan13_raw; - packet.chan14_raw = chan14_raw; - packet.chan15_raw = chan15_raw; - packet.chan16_raw = chan16_raw; - packet.chan17_raw = chan17_raw; - packet.chan18_raw = chan18_raw; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE, (const char *)&packet, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_MIN_LEN, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_CRC); -#endif -} - -/** - * @brief Send a rc_channels_override message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_rc_channels_override_send_struct(mavlink_channel_t chan, const mavlink_rc_channels_override_t* rc_channels_override) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_rc_channels_override_send(chan, rc_channels_override->target_system, rc_channels_override->target_component, rc_channels_override->chan1_raw, rc_channels_override->chan2_raw, rc_channels_override->chan3_raw, rc_channels_override->chan4_raw, rc_channels_override->chan5_raw, rc_channels_override->chan6_raw, rc_channels_override->chan7_raw, rc_channels_override->chan8_raw, rc_channels_override->chan9_raw, rc_channels_override->chan10_raw, rc_channels_override->chan11_raw, rc_channels_override->chan12_raw, rc_channels_override->chan13_raw, rc_channels_override->chan14_raw, rc_channels_override->chan15_raw, rc_channels_override->chan16_raw, rc_channels_override->chan17_raw, rc_channels_override->chan18_raw); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE, (const char *)rc_channels_override, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_MIN_LEN, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_CRC); -#endif -} - -#if MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_rc_channels_override_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t chan1_raw, uint16_t chan2_raw, uint16_t chan3_raw, uint16_t chan4_raw, uint16_t chan5_raw, uint16_t chan6_raw, uint16_t chan7_raw, uint16_t chan8_raw, uint16_t chan9_raw, uint16_t chan10_raw, uint16_t chan11_raw, uint16_t chan12_raw, uint16_t chan13_raw, uint16_t chan14_raw, uint16_t chan15_raw, uint16_t chan16_raw, uint16_t chan17_raw, uint16_t chan18_raw) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint16_t(buf, 0, chan1_raw); - _mav_put_uint16_t(buf, 2, chan2_raw); - _mav_put_uint16_t(buf, 4, chan3_raw); - _mav_put_uint16_t(buf, 6, chan4_raw); - _mav_put_uint16_t(buf, 8, chan5_raw); - _mav_put_uint16_t(buf, 10, chan6_raw); - _mav_put_uint16_t(buf, 12, chan7_raw); - _mav_put_uint16_t(buf, 14, chan8_raw); - _mav_put_uint8_t(buf, 16, target_system); - _mav_put_uint8_t(buf, 17, target_component); - _mav_put_uint16_t(buf, 18, chan9_raw); - _mav_put_uint16_t(buf, 20, chan10_raw); - _mav_put_uint16_t(buf, 22, chan11_raw); - _mav_put_uint16_t(buf, 24, chan12_raw); - _mav_put_uint16_t(buf, 26, chan13_raw); - _mav_put_uint16_t(buf, 28, chan14_raw); - _mav_put_uint16_t(buf, 30, chan15_raw); - _mav_put_uint16_t(buf, 32, chan16_raw); - _mav_put_uint16_t(buf, 34, chan17_raw); - _mav_put_uint16_t(buf, 36, chan18_raw); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE, buf, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_MIN_LEN, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_CRC); -#else - mavlink_rc_channels_override_t *packet = (mavlink_rc_channels_override_t *)msgbuf; - packet->chan1_raw = chan1_raw; - packet->chan2_raw = chan2_raw; - packet->chan3_raw = chan3_raw; - packet->chan4_raw = chan4_raw; - packet->chan5_raw = chan5_raw; - packet->chan6_raw = chan6_raw; - packet->chan7_raw = chan7_raw; - packet->chan8_raw = chan8_raw; - packet->target_system = target_system; - packet->target_component = target_component; - packet->chan9_raw = chan9_raw; - packet->chan10_raw = chan10_raw; - packet->chan11_raw = chan11_raw; - packet->chan12_raw = chan12_raw; - packet->chan13_raw = chan13_raw; - packet->chan14_raw = chan14_raw; - packet->chan15_raw = chan15_raw; - packet->chan16_raw = chan16_raw; - packet->chan17_raw = chan17_raw; - packet->chan18_raw = chan18_raw; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE, (const char *)packet, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_MIN_LEN, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_CRC); -#endif -} -#endif - -#endif - -// MESSAGE RC_CHANNELS_OVERRIDE UNPACKING - - -/** - * @brief Get field target_system from rc_channels_override message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_rc_channels_override_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 16); -} - -/** - * @brief Get field target_component from rc_channels_override message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_rc_channels_override_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 17); -} - -/** - * @brief Get field chan1_raw from rc_channels_override message - * - * @return [us] RC channel 1 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio. - */ -static inline uint16_t mavlink_msg_rc_channels_override_get_chan1_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 0); -} - -/** - * @brief Get field chan2_raw from rc_channels_override message - * - * @return [us] RC channel 2 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio. - */ -static inline uint16_t mavlink_msg_rc_channels_override_get_chan2_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 2); -} - -/** - * @brief Get field chan3_raw from rc_channels_override message - * - * @return [us] RC channel 3 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio. - */ -static inline uint16_t mavlink_msg_rc_channels_override_get_chan3_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 4); -} - -/** - * @brief Get field chan4_raw from rc_channels_override message - * - * @return [us] RC channel 4 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio. - */ -static inline uint16_t mavlink_msg_rc_channels_override_get_chan4_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 6); -} - -/** - * @brief Get field chan5_raw from rc_channels_override message - * - * @return [us] RC channel 5 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio. - */ -static inline uint16_t mavlink_msg_rc_channels_override_get_chan5_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 8); -} - -/** - * @brief Get field chan6_raw from rc_channels_override message - * - * @return [us] RC channel 6 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio. - */ -static inline uint16_t mavlink_msg_rc_channels_override_get_chan6_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 10); -} - -/** - * @brief Get field chan7_raw from rc_channels_override message - * - * @return [us] RC channel 7 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio. - */ -static inline uint16_t mavlink_msg_rc_channels_override_get_chan7_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 12); -} - -/** - * @brief Get field chan8_raw from rc_channels_override message - * - * @return [us] RC channel 8 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio. - */ -static inline uint16_t mavlink_msg_rc_channels_override_get_chan8_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 14); -} - -/** - * @brief Get field chan9_raw from rc_channels_override message - * - * @return [us] RC channel 9 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio. - */ -static inline uint16_t mavlink_msg_rc_channels_override_get_chan9_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 18); -} - -/** - * @brief Get field chan10_raw from rc_channels_override message - * - * @return [us] RC channel 10 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio. - */ -static inline uint16_t mavlink_msg_rc_channels_override_get_chan10_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 20); -} - -/** - * @brief Get field chan11_raw from rc_channels_override message - * - * @return [us] RC channel 11 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio. - */ -static inline uint16_t mavlink_msg_rc_channels_override_get_chan11_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 22); -} - -/** - * @brief Get field chan12_raw from rc_channels_override message - * - * @return [us] RC channel 12 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio. - */ -static inline uint16_t mavlink_msg_rc_channels_override_get_chan12_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 24); -} - -/** - * @brief Get field chan13_raw from rc_channels_override message - * - * @return [us] RC channel 13 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio. - */ -static inline uint16_t mavlink_msg_rc_channels_override_get_chan13_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 26); -} - -/** - * @brief Get field chan14_raw from rc_channels_override message - * - * @return [us] RC channel 14 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio. - */ -static inline uint16_t mavlink_msg_rc_channels_override_get_chan14_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 28); -} - -/** - * @brief Get field chan15_raw from rc_channels_override message - * - * @return [us] RC channel 15 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio. - */ -static inline uint16_t mavlink_msg_rc_channels_override_get_chan15_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 30); -} - -/** - * @brief Get field chan16_raw from rc_channels_override message - * - * @return [us] RC channel 16 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio. - */ -static inline uint16_t mavlink_msg_rc_channels_override_get_chan16_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 32); -} - -/** - * @brief Get field chan17_raw from rc_channels_override message - * - * @return [us] RC channel 17 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio. - */ -static inline uint16_t mavlink_msg_rc_channels_override_get_chan17_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 34); -} - -/** - * @brief Get field chan18_raw from rc_channels_override message - * - * @return [us] RC channel 18 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio. - */ -static inline uint16_t mavlink_msg_rc_channels_override_get_chan18_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 36); -} - -/** - * @brief Decode a rc_channels_override message into a struct - * - * @param msg The message to decode - * @param rc_channels_override C-struct to decode the message contents into - */ -static inline void mavlink_msg_rc_channels_override_decode(const mavlink_message_t* msg, mavlink_rc_channels_override_t* rc_channels_override) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - rc_channels_override->chan1_raw = mavlink_msg_rc_channels_override_get_chan1_raw(msg); - rc_channels_override->chan2_raw = mavlink_msg_rc_channels_override_get_chan2_raw(msg); - rc_channels_override->chan3_raw = mavlink_msg_rc_channels_override_get_chan3_raw(msg); - rc_channels_override->chan4_raw = mavlink_msg_rc_channels_override_get_chan4_raw(msg); - rc_channels_override->chan5_raw = mavlink_msg_rc_channels_override_get_chan5_raw(msg); - rc_channels_override->chan6_raw = mavlink_msg_rc_channels_override_get_chan6_raw(msg); - rc_channels_override->chan7_raw = mavlink_msg_rc_channels_override_get_chan7_raw(msg); - rc_channels_override->chan8_raw = mavlink_msg_rc_channels_override_get_chan8_raw(msg); - rc_channels_override->target_system = mavlink_msg_rc_channels_override_get_target_system(msg); - rc_channels_override->target_component = mavlink_msg_rc_channels_override_get_target_component(msg); - rc_channels_override->chan9_raw = mavlink_msg_rc_channels_override_get_chan9_raw(msg); - rc_channels_override->chan10_raw = mavlink_msg_rc_channels_override_get_chan10_raw(msg); - rc_channels_override->chan11_raw = mavlink_msg_rc_channels_override_get_chan11_raw(msg); - rc_channels_override->chan12_raw = mavlink_msg_rc_channels_override_get_chan12_raw(msg); - rc_channels_override->chan13_raw = mavlink_msg_rc_channels_override_get_chan13_raw(msg); - rc_channels_override->chan14_raw = mavlink_msg_rc_channels_override_get_chan14_raw(msg); - rc_channels_override->chan15_raw = mavlink_msg_rc_channels_override_get_chan15_raw(msg); - rc_channels_override->chan16_raw = mavlink_msg_rc_channels_override_get_chan16_raw(msg); - rc_channels_override->chan17_raw = mavlink_msg_rc_channels_override_get_chan17_raw(msg); - rc_channels_override->chan18_raw = mavlink_msg_rc_channels_override_get_chan18_raw(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN? msg->len : MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN; - memset(rc_channels_override, 0, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN); - memcpy(rc_channels_override, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_rc_channels_raw.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_rc_channels_raw.h deleted file mode 100644 index af768381..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_rc_channels_raw.h +++ /dev/null @@ -1,463 +0,0 @@ -#pragma once -// MESSAGE RC_CHANNELS_RAW PACKING - -#define MAVLINK_MSG_ID_RC_CHANNELS_RAW 35 - - -typedef struct __mavlink_rc_channels_raw_t { - uint32_t time_boot_ms; /*< [ms] Timestamp (time since system boot).*/ - uint16_t chan1_raw; /*< [us] RC channel 1 value.*/ - uint16_t chan2_raw; /*< [us] RC channel 2 value.*/ - uint16_t chan3_raw; /*< [us] RC channel 3 value.*/ - uint16_t chan4_raw; /*< [us] RC channel 4 value.*/ - uint16_t chan5_raw; /*< [us] RC channel 5 value.*/ - uint16_t chan6_raw; /*< [us] RC channel 6 value.*/ - uint16_t chan7_raw; /*< [us] RC channel 7 value.*/ - uint16_t chan8_raw; /*< [us] RC channel 8 value.*/ - uint8_t port; /*< Servo output port (set of 8 outputs = 1 port). Flight stacks running on Pixhawk should use: 0 = MAIN, 1 = AUX.*/ - uint8_t rssi; /*< Receive signal strength indicator in device-dependent units/scale. Values: [0-254], UINT8_MAX: invalid/unknown.*/ -} mavlink_rc_channels_raw_t; - -#define MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN 22 -#define MAVLINK_MSG_ID_RC_CHANNELS_RAW_MIN_LEN 22 -#define MAVLINK_MSG_ID_35_LEN 22 -#define MAVLINK_MSG_ID_35_MIN_LEN 22 - -#define MAVLINK_MSG_ID_RC_CHANNELS_RAW_CRC 244 -#define MAVLINK_MSG_ID_35_CRC 244 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_RC_CHANNELS_RAW { \ - 35, \ - "RC_CHANNELS_RAW", \ - 11, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_rc_channels_raw_t, time_boot_ms) }, \ - { "port", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_rc_channels_raw_t, port) }, \ - { "chan1_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_rc_channels_raw_t, chan1_raw) }, \ - { "chan2_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_rc_channels_raw_t, chan2_raw) }, \ - { "chan3_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_rc_channels_raw_t, chan3_raw) }, \ - { "chan4_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_rc_channels_raw_t, chan4_raw) }, \ - { "chan5_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_rc_channels_raw_t, chan5_raw) }, \ - { "chan6_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_rc_channels_raw_t, chan6_raw) }, \ - { "chan7_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_rc_channels_raw_t, chan7_raw) }, \ - { "chan8_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_rc_channels_raw_t, chan8_raw) }, \ - { "rssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 21, offsetof(mavlink_rc_channels_raw_t, rssi) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_RC_CHANNELS_RAW { \ - "RC_CHANNELS_RAW", \ - 11, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_rc_channels_raw_t, time_boot_ms) }, \ - { "port", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_rc_channels_raw_t, port) }, \ - { "chan1_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_rc_channels_raw_t, chan1_raw) }, \ - { "chan2_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_rc_channels_raw_t, chan2_raw) }, \ - { "chan3_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_rc_channels_raw_t, chan3_raw) }, \ - { "chan4_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_rc_channels_raw_t, chan4_raw) }, \ - { "chan5_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_rc_channels_raw_t, chan5_raw) }, \ - { "chan6_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_rc_channels_raw_t, chan6_raw) }, \ - { "chan7_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_rc_channels_raw_t, chan7_raw) }, \ - { "chan8_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_rc_channels_raw_t, chan8_raw) }, \ - { "rssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 21, offsetof(mavlink_rc_channels_raw_t, rssi) }, \ - } \ -} -#endif - -/** - * @brief Pack a rc_channels_raw message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param time_boot_ms [ms] Timestamp (time since system boot). - * @param port Servo output port (set of 8 outputs = 1 port). Flight stacks running on Pixhawk should use: 0 = MAIN, 1 = AUX. - * @param chan1_raw [us] RC channel 1 value. - * @param chan2_raw [us] RC channel 2 value. - * @param chan3_raw [us] RC channel 3 value. - * @param chan4_raw [us] RC channel 4 value. - * @param chan5_raw [us] RC channel 5 value. - * @param chan6_raw [us] RC channel 6 value. - * @param chan7_raw [us] RC channel 7 value. - * @param chan8_raw [us] RC channel 8 value. - * @param rssi Receive signal strength indicator in device-dependent units/scale. Values: [0-254], UINT8_MAX: invalid/unknown. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_rc_channels_raw_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint32_t time_boot_ms, uint8_t port, uint16_t chan1_raw, uint16_t chan2_raw, uint16_t chan3_raw, uint16_t chan4_raw, uint16_t chan5_raw, uint16_t chan6_raw, uint16_t chan7_raw, uint16_t chan8_raw, uint8_t rssi) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_uint16_t(buf, 4, chan1_raw); - _mav_put_uint16_t(buf, 6, chan2_raw); - _mav_put_uint16_t(buf, 8, chan3_raw); - _mav_put_uint16_t(buf, 10, chan4_raw); - _mav_put_uint16_t(buf, 12, chan5_raw); - _mav_put_uint16_t(buf, 14, chan6_raw); - _mav_put_uint16_t(buf, 16, chan7_raw); - _mav_put_uint16_t(buf, 18, chan8_raw); - _mav_put_uint8_t(buf, 20, port); - _mav_put_uint8_t(buf, 21, rssi); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN); -#else - mavlink_rc_channels_raw_t packet; - packet.time_boot_ms = time_boot_ms; - packet.chan1_raw = chan1_raw; - packet.chan2_raw = chan2_raw; - packet.chan3_raw = chan3_raw; - packet.chan4_raw = chan4_raw; - packet.chan5_raw = chan5_raw; - packet.chan6_raw = chan6_raw; - packet.chan7_raw = chan7_raw; - packet.chan8_raw = chan8_raw; - packet.port = port; - packet.rssi = rssi; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_RC_CHANNELS_RAW; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RC_CHANNELS_RAW_MIN_LEN, MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN, MAVLINK_MSG_ID_RC_CHANNELS_RAW_CRC); -} - -/** - * @brief Pack a rc_channels_raw message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_boot_ms [ms] Timestamp (time since system boot). - * @param port Servo output port (set of 8 outputs = 1 port). Flight stacks running on Pixhawk should use: 0 = MAIN, 1 = AUX. - * @param chan1_raw [us] RC channel 1 value. - * @param chan2_raw [us] RC channel 2 value. - * @param chan3_raw [us] RC channel 3 value. - * @param chan4_raw [us] RC channel 4 value. - * @param chan5_raw [us] RC channel 5 value. - * @param chan6_raw [us] RC channel 6 value. - * @param chan7_raw [us] RC channel 7 value. - * @param chan8_raw [us] RC channel 8 value. - * @param rssi Receive signal strength indicator in device-dependent units/scale. Values: [0-254], UINT8_MAX: invalid/unknown. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_rc_channels_raw_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint32_t time_boot_ms,uint8_t port,uint16_t chan1_raw,uint16_t chan2_raw,uint16_t chan3_raw,uint16_t chan4_raw,uint16_t chan5_raw,uint16_t chan6_raw,uint16_t chan7_raw,uint16_t chan8_raw,uint8_t rssi) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_uint16_t(buf, 4, chan1_raw); - _mav_put_uint16_t(buf, 6, chan2_raw); - _mav_put_uint16_t(buf, 8, chan3_raw); - _mav_put_uint16_t(buf, 10, chan4_raw); - _mav_put_uint16_t(buf, 12, chan5_raw); - _mav_put_uint16_t(buf, 14, chan6_raw); - _mav_put_uint16_t(buf, 16, chan7_raw); - _mav_put_uint16_t(buf, 18, chan8_raw); - _mav_put_uint8_t(buf, 20, port); - _mav_put_uint8_t(buf, 21, rssi); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN); -#else - mavlink_rc_channels_raw_t packet; - packet.time_boot_ms = time_boot_ms; - packet.chan1_raw = chan1_raw; - packet.chan2_raw = chan2_raw; - packet.chan3_raw = chan3_raw; - packet.chan4_raw = chan4_raw; - packet.chan5_raw = chan5_raw; - packet.chan6_raw = chan6_raw; - packet.chan7_raw = chan7_raw; - packet.chan8_raw = chan8_raw; - packet.port = port; - packet.rssi = rssi; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_RC_CHANNELS_RAW; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RC_CHANNELS_RAW_MIN_LEN, MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN, MAVLINK_MSG_ID_RC_CHANNELS_RAW_CRC); -} - -/** - * @brief Encode a rc_channels_raw struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param rc_channels_raw C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_rc_channels_raw_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_rc_channels_raw_t* rc_channels_raw) -{ - return mavlink_msg_rc_channels_raw_pack(system_id, component_id, msg, rc_channels_raw->time_boot_ms, rc_channels_raw->port, rc_channels_raw->chan1_raw, rc_channels_raw->chan2_raw, rc_channels_raw->chan3_raw, rc_channels_raw->chan4_raw, rc_channels_raw->chan5_raw, rc_channels_raw->chan6_raw, rc_channels_raw->chan7_raw, rc_channels_raw->chan8_raw, rc_channels_raw->rssi); -} - -/** - * @brief Encode a rc_channels_raw struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param rc_channels_raw C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_rc_channels_raw_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_rc_channels_raw_t* rc_channels_raw) -{ - return mavlink_msg_rc_channels_raw_pack_chan(system_id, component_id, chan, msg, rc_channels_raw->time_boot_ms, rc_channels_raw->port, rc_channels_raw->chan1_raw, rc_channels_raw->chan2_raw, rc_channels_raw->chan3_raw, rc_channels_raw->chan4_raw, rc_channels_raw->chan5_raw, rc_channels_raw->chan6_raw, rc_channels_raw->chan7_raw, rc_channels_raw->chan8_raw, rc_channels_raw->rssi); -} - -/** - * @brief Send a rc_channels_raw message - * @param chan MAVLink channel to send the message - * - * @param time_boot_ms [ms] Timestamp (time since system boot). - * @param port Servo output port (set of 8 outputs = 1 port). Flight stacks running on Pixhawk should use: 0 = MAIN, 1 = AUX. - * @param chan1_raw [us] RC channel 1 value. - * @param chan2_raw [us] RC channel 2 value. - * @param chan3_raw [us] RC channel 3 value. - * @param chan4_raw [us] RC channel 4 value. - * @param chan5_raw [us] RC channel 5 value. - * @param chan6_raw [us] RC channel 6 value. - * @param chan7_raw [us] RC channel 7 value. - * @param chan8_raw [us] RC channel 8 value. - * @param rssi Receive signal strength indicator in device-dependent units/scale. Values: [0-254], UINT8_MAX: invalid/unknown. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_rc_channels_raw_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t port, uint16_t chan1_raw, uint16_t chan2_raw, uint16_t chan3_raw, uint16_t chan4_raw, uint16_t chan5_raw, uint16_t chan6_raw, uint16_t chan7_raw, uint16_t chan8_raw, uint8_t rssi) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_uint16_t(buf, 4, chan1_raw); - _mav_put_uint16_t(buf, 6, chan2_raw); - _mav_put_uint16_t(buf, 8, chan3_raw); - _mav_put_uint16_t(buf, 10, chan4_raw); - _mav_put_uint16_t(buf, 12, chan5_raw); - _mav_put_uint16_t(buf, 14, chan6_raw); - _mav_put_uint16_t(buf, 16, chan7_raw); - _mav_put_uint16_t(buf, 18, chan8_raw); - _mav_put_uint8_t(buf, 20, port); - _mav_put_uint8_t(buf, 21, rssi); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_RAW, buf, MAVLINK_MSG_ID_RC_CHANNELS_RAW_MIN_LEN, MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN, MAVLINK_MSG_ID_RC_CHANNELS_RAW_CRC); -#else - mavlink_rc_channels_raw_t packet; - packet.time_boot_ms = time_boot_ms; - packet.chan1_raw = chan1_raw; - packet.chan2_raw = chan2_raw; - packet.chan3_raw = chan3_raw; - packet.chan4_raw = chan4_raw; - packet.chan5_raw = chan5_raw; - packet.chan6_raw = chan6_raw; - packet.chan7_raw = chan7_raw; - packet.chan8_raw = chan8_raw; - packet.port = port; - packet.rssi = rssi; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_RAW, (const char *)&packet, MAVLINK_MSG_ID_RC_CHANNELS_RAW_MIN_LEN, MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN, MAVLINK_MSG_ID_RC_CHANNELS_RAW_CRC); -#endif -} - -/** - * @brief Send a rc_channels_raw message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_rc_channels_raw_send_struct(mavlink_channel_t chan, const mavlink_rc_channels_raw_t* rc_channels_raw) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_rc_channels_raw_send(chan, rc_channels_raw->time_boot_ms, rc_channels_raw->port, rc_channels_raw->chan1_raw, rc_channels_raw->chan2_raw, rc_channels_raw->chan3_raw, rc_channels_raw->chan4_raw, rc_channels_raw->chan5_raw, rc_channels_raw->chan6_raw, rc_channels_raw->chan7_raw, rc_channels_raw->chan8_raw, rc_channels_raw->rssi); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_RAW, (const char *)rc_channels_raw, MAVLINK_MSG_ID_RC_CHANNELS_RAW_MIN_LEN, MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN, MAVLINK_MSG_ID_RC_CHANNELS_RAW_CRC); -#endif -} - -#if MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_rc_channels_raw_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t port, uint16_t chan1_raw, uint16_t chan2_raw, uint16_t chan3_raw, uint16_t chan4_raw, uint16_t chan5_raw, uint16_t chan6_raw, uint16_t chan7_raw, uint16_t chan8_raw, uint8_t rssi) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_uint16_t(buf, 4, chan1_raw); - _mav_put_uint16_t(buf, 6, chan2_raw); - _mav_put_uint16_t(buf, 8, chan3_raw); - _mav_put_uint16_t(buf, 10, chan4_raw); - _mav_put_uint16_t(buf, 12, chan5_raw); - _mav_put_uint16_t(buf, 14, chan6_raw); - _mav_put_uint16_t(buf, 16, chan7_raw); - _mav_put_uint16_t(buf, 18, chan8_raw); - _mav_put_uint8_t(buf, 20, port); - _mav_put_uint8_t(buf, 21, rssi); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_RAW, buf, MAVLINK_MSG_ID_RC_CHANNELS_RAW_MIN_LEN, MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN, MAVLINK_MSG_ID_RC_CHANNELS_RAW_CRC); -#else - mavlink_rc_channels_raw_t *packet = (mavlink_rc_channels_raw_t *)msgbuf; - packet->time_boot_ms = time_boot_ms; - packet->chan1_raw = chan1_raw; - packet->chan2_raw = chan2_raw; - packet->chan3_raw = chan3_raw; - packet->chan4_raw = chan4_raw; - packet->chan5_raw = chan5_raw; - packet->chan6_raw = chan6_raw; - packet->chan7_raw = chan7_raw; - packet->chan8_raw = chan8_raw; - packet->port = port; - packet->rssi = rssi; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_RAW, (const char *)packet, MAVLINK_MSG_ID_RC_CHANNELS_RAW_MIN_LEN, MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN, MAVLINK_MSG_ID_RC_CHANNELS_RAW_CRC); -#endif -} -#endif - -#endif - -// MESSAGE RC_CHANNELS_RAW UNPACKING - - -/** - * @brief Get field time_boot_ms from rc_channels_raw message - * - * @return [ms] Timestamp (time since system boot). - */ -static inline uint32_t mavlink_msg_rc_channels_raw_get_time_boot_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field port from rc_channels_raw message - * - * @return Servo output port (set of 8 outputs = 1 port). Flight stacks running on Pixhawk should use: 0 = MAIN, 1 = AUX. - */ -static inline uint8_t mavlink_msg_rc_channels_raw_get_port(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 20); -} - -/** - * @brief Get field chan1_raw from rc_channels_raw message - * - * @return [us] RC channel 1 value. - */ -static inline uint16_t mavlink_msg_rc_channels_raw_get_chan1_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 4); -} - -/** - * @brief Get field chan2_raw from rc_channels_raw message - * - * @return [us] RC channel 2 value. - */ -static inline uint16_t mavlink_msg_rc_channels_raw_get_chan2_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 6); -} - -/** - * @brief Get field chan3_raw from rc_channels_raw message - * - * @return [us] RC channel 3 value. - */ -static inline uint16_t mavlink_msg_rc_channels_raw_get_chan3_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 8); -} - -/** - * @brief Get field chan4_raw from rc_channels_raw message - * - * @return [us] RC channel 4 value. - */ -static inline uint16_t mavlink_msg_rc_channels_raw_get_chan4_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 10); -} - -/** - * @brief Get field chan5_raw from rc_channels_raw message - * - * @return [us] RC channel 5 value. - */ -static inline uint16_t mavlink_msg_rc_channels_raw_get_chan5_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 12); -} - -/** - * @brief Get field chan6_raw from rc_channels_raw message - * - * @return [us] RC channel 6 value. - */ -static inline uint16_t mavlink_msg_rc_channels_raw_get_chan6_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 14); -} - -/** - * @brief Get field chan7_raw from rc_channels_raw message - * - * @return [us] RC channel 7 value. - */ -static inline uint16_t mavlink_msg_rc_channels_raw_get_chan7_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 16); -} - -/** - * @brief Get field chan8_raw from rc_channels_raw message - * - * @return [us] RC channel 8 value. - */ -static inline uint16_t mavlink_msg_rc_channels_raw_get_chan8_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 18); -} - -/** - * @brief Get field rssi from rc_channels_raw message - * - * @return Receive signal strength indicator in device-dependent units/scale. Values: [0-254], UINT8_MAX: invalid/unknown. - */ -static inline uint8_t mavlink_msg_rc_channels_raw_get_rssi(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 21); -} - -/** - * @brief Decode a rc_channels_raw message into a struct - * - * @param msg The message to decode - * @param rc_channels_raw C-struct to decode the message contents into - */ -static inline void mavlink_msg_rc_channels_raw_decode(const mavlink_message_t* msg, mavlink_rc_channels_raw_t* rc_channels_raw) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - rc_channels_raw->time_boot_ms = mavlink_msg_rc_channels_raw_get_time_boot_ms(msg); - rc_channels_raw->chan1_raw = mavlink_msg_rc_channels_raw_get_chan1_raw(msg); - rc_channels_raw->chan2_raw = mavlink_msg_rc_channels_raw_get_chan2_raw(msg); - rc_channels_raw->chan3_raw = mavlink_msg_rc_channels_raw_get_chan3_raw(msg); - rc_channels_raw->chan4_raw = mavlink_msg_rc_channels_raw_get_chan4_raw(msg); - rc_channels_raw->chan5_raw = mavlink_msg_rc_channels_raw_get_chan5_raw(msg); - rc_channels_raw->chan6_raw = mavlink_msg_rc_channels_raw_get_chan6_raw(msg); - rc_channels_raw->chan7_raw = mavlink_msg_rc_channels_raw_get_chan7_raw(msg); - rc_channels_raw->chan8_raw = mavlink_msg_rc_channels_raw_get_chan8_raw(msg); - rc_channels_raw->port = mavlink_msg_rc_channels_raw_get_port(msg); - rc_channels_raw->rssi = mavlink_msg_rc_channels_raw_get_rssi(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN? msg->len : MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN; - memset(rc_channels_raw, 0, MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN); - memcpy(rc_channels_raw, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_rc_channels_scaled.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_rc_channels_scaled.h deleted file mode 100644 index bc5dea78..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_rc_channels_scaled.h +++ /dev/null @@ -1,463 +0,0 @@ -#pragma once -// MESSAGE RC_CHANNELS_SCALED PACKING - -#define MAVLINK_MSG_ID_RC_CHANNELS_SCALED 34 - - -typedef struct __mavlink_rc_channels_scaled_t { - uint32_t time_boot_ms; /*< [ms] Timestamp (time since system boot).*/ - int16_t chan1_scaled; /*< RC channel 1 value scaled.*/ - int16_t chan2_scaled; /*< RC channel 2 value scaled.*/ - int16_t chan3_scaled; /*< RC channel 3 value scaled.*/ - int16_t chan4_scaled; /*< RC channel 4 value scaled.*/ - int16_t chan5_scaled; /*< RC channel 5 value scaled.*/ - int16_t chan6_scaled; /*< RC channel 6 value scaled.*/ - int16_t chan7_scaled; /*< RC channel 7 value scaled.*/ - int16_t chan8_scaled; /*< RC channel 8 value scaled.*/ - uint8_t port; /*< Servo output port (set of 8 outputs = 1 port). Flight stacks running on Pixhawk should use: 0 = MAIN, 1 = AUX.*/ - uint8_t rssi; /*< Receive signal strength indicator in device-dependent units/scale. Values: [0-254], UINT8_MAX: invalid/unknown.*/ -} mavlink_rc_channels_scaled_t; - -#define MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN 22 -#define MAVLINK_MSG_ID_RC_CHANNELS_SCALED_MIN_LEN 22 -#define MAVLINK_MSG_ID_34_LEN 22 -#define MAVLINK_MSG_ID_34_MIN_LEN 22 - -#define MAVLINK_MSG_ID_RC_CHANNELS_SCALED_CRC 237 -#define MAVLINK_MSG_ID_34_CRC 237 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_RC_CHANNELS_SCALED { \ - 34, \ - "RC_CHANNELS_SCALED", \ - 11, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_rc_channels_scaled_t, time_boot_ms) }, \ - { "port", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_rc_channels_scaled_t, port) }, \ - { "chan1_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 4, offsetof(mavlink_rc_channels_scaled_t, chan1_scaled) }, \ - { "chan2_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 6, offsetof(mavlink_rc_channels_scaled_t, chan2_scaled) }, \ - { "chan3_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_rc_channels_scaled_t, chan3_scaled) }, \ - { "chan4_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 10, offsetof(mavlink_rc_channels_scaled_t, chan4_scaled) }, \ - { "chan5_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_rc_channels_scaled_t, chan5_scaled) }, \ - { "chan6_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_rc_channels_scaled_t, chan6_scaled) }, \ - { "chan7_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_rc_channels_scaled_t, chan7_scaled) }, \ - { "chan8_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 18, offsetof(mavlink_rc_channels_scaled_t, chan8_scaled) }, \ - { "rssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 21, offsetof(mavlink_rc_channels_scaled_t, rssi) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_RC_CHANNELS_SCALED { \ - "RC_CHANNELS_SCALED", \ - 11, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_rc_channels_scaled_t, time_boot_ms) }, \ - { "port", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_rc_channels_scaled_t, port) }, \ - { "chan1_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 4, offsetof(mavlink_rc_channels_scaled_t, chan1_scaled) }, \ - { "chan2_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 6, offsetof(mavlink_rc_channels_scaled_t, chan2_scaled) }, \ - { "chan3_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_rc_channels_scaled_t, chan3_scaled) }, \ - { "chan4_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 10, offsetof(mavlink_rc_channels_scaled_t, chan4_scaled) }, \ - { "chan5_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_rc_channels_scaled_t, chan5_scaled) }, \ - { "chan6_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_rc_channels_scaled_t, chan6_scaled) }, \ - { "chan7_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_rc_channels_scaled_t, chan7_scaled) }, \ - { "chan8_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 18, offsetof(mavlink_rc_channels_scaled_t, chan8_scaled) }, \ - { "rssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 21, offsetof(mavlink_rc_channels_scaled_t, rssi) }, \ - } \ -} -#endif - -/** - * @brief Pack a rc_channels_scaled message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param time_boot_ms [ms] Timestamp (time since system boot). - * @param port Servo output port (set of 8 outputs = 1 port). Flight stacks running on Pixhawk should use: 0 = MAIN, 1 = AUX. - * @param chan1_scaled RC channel 1 value scaled. - * @param chan2_scaled RC channel 2 value scaled. - * @param chan3_scaled RC channel 3 value scaled. - * @param chan4_scaled RC channel 4 value scaled. - * @param chan5_scaled RC channel 5 value scaled. - * @param chan6_scaled RC channel 6 value scaled. - * @param chan7_scaled RC channel 7 value scaled. - * @param chan8_scaled RC channel 8 value scaled. - * @param rssi Receive signal strength indicator in device-dependent units/scale. Values: [0-254], UINT8_MAX: invalid/unknown. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_rc_channels_scaled_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint32_t time_boot_ms, uint8_t port, int16_t chan1_scaled, int16_t chan2_scaled, int16_t chan3_scaled, int16_t chan4_scaled, int16_t chan5_scaled, int16_t chan6_scaled, int16_t chan7_scaled, int16_t chan8_scaled, uint8_t rssi) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_int16_t(buf, 4, chan1_scaled); - _mav_put_int16_t(buf, 6, chan2_scaled); - _mav_put_int16_t(buf, 8, chan3_scaled); - _mav_put_int16_t(buf, 10, chan4_scaled); - _mav_put_int16_t(buf, 12, chan5_scaled); - _mav_put_int16_t(buf, 14, chan6_scaled); - _mav_put_int16_t(buf, 16, chan7_scaled); - _mav_put_int16_t(buf, 18, chan8_scaled); - _mav_put_uint8_t(buf, 20, port); - _mav_put_uint8_t(buf, 21, rssi); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN); -#else - mavlink_rc_channels_scaled_t packet; - packet.time_boot_ms = time_boot_ms; - packet.chan1_scaled = chan1_scaled; - packet.chan2_scaled = chan2_scaled; - packet.chan3_scaled = chan3_scaled; - packet.chan4_scaled = chan4_scaled; - packet.chan5_scaled = chan5_scaled; - packet.chan6_scaled = chan6_scaled; - packet.chan7_scaled = chan7_scaled; - packet.chan8_scaled = chan8_scaled; - packet.port = port; - packet.rssi = rssi; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_RC_CHANNELS_SCALED; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_MIN_LEN, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_CRC); -} - -/** - * @brief Pack a rc_channels_scaled message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_boot_ms [ms] Timestamp (time since system boot). - * @param port Servo output port (set of 8 outputs = 1 port). Flight stacks running on Pixhawk should use: 0 = MAIN, 1 = AUX. - * @param chan1_scaled RC channel 1 value scaled. - * @param chan2_scaled RC channel 2 value scaled. - * @param chan3_scaled RC channel 3 value scaled. - * @param chan4_scaled RC channel 4 value scaled. - * @param chan5_scaled RC channel 5 value scaled. - * @param chan6_scaled RC channel 6 value scaled. - * @param chan7_scaled RC channel 7 value scaled. - * @param chan8_scaled RC channel 8 value scaled. - * @param rssi Receive signal strength indicator in device-dependent units/scale. Values: [0-254], UINT8_MAX: invalid/unknown. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_rc_channels_scaled_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint32_t time_boot_ms,uint8_t port,int16_t chan1_scaled,int16_t chan2_scaled,int16_t chan3_scaled,int16_t chan4_scaled,int16_t chan5_scaled,int16_t chan6_scaled,int16_t chan7_scaled,int16_t chan8_scaled,uint8_t rssi) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_int16_t(buf, 4, chan1_scaled); - _mav_put_int16_t(buf, 6, chan2_scaled); - _mav_put_int16_t(buf, 8, chan3_scaled); - _mav_put_int16_t(buf, 10, chan4_scaled); - _mav_put_int16_t(buf, 12, chan5_scaled); - _mav_put_int16_t(buf, 14, chan6_scaled); - _mav_put_int16_t(buf, 16, chan7_scaled); - _mav_put_int16_t(buf, 18, chan8_scaled); - _mav_put_uint8_t(buf, 20, port); - _mav_put_uint8_t(buf, 21, rssi); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN); -#else - mavlink_rc_channels_scaled_t packet; - packet.time_boot_ms = time_boot_ms; - packet.chan1_scaled = chan1_scaled; - packet.chan2_scaled = chan2_scaled; - packet.chan3_scaled = chan3_scaled; - packet.chan4_scaled = chan4_scaled; - packet.chan5_scaled = chan5_scaled; - packet.chan6_scaled = chan6_scaled; - packet.chan7_scaled = chan7_scaled; - packet.chan8_scaled = chan8_scaled; - packet.port = port; - packet.rssi = rssi; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_RC_CHANNELS_SCALED; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_MIN_LEN, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_CRC); -} - -/** - * @brief Encode a rc_channels_scaled struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param rc_channels_scaled C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_rc_channels_scaled_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_rc_channels_scaled_t* rc_channels_scaled) -{ - return mavlink_msg_rc_channels_scaled_pack(system_id, component_id, msg, rc_channels_scaled->time_boot_ms, rc_channels_scaled->port, rc_channels_scaled->chan1_scaled, rc_channels_scaled->chan2_scaled, rc_channels_scaled->chan3_scaled, rc_channels_scaled->chan4_scaled, rc_channels_scaled->chan5_scaled, rc_channels_scaled->chan6_scaled, rc_channels_scaled->chan7_scaled, rc_channels_scaled->chan8_scaled, rc_channels_scaled->rssi); -} - -/** - * @brief Encode a rc_channels_scaled struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param rc_channels_scaled C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_rc_channels_scaled_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_rc_channels_scaled_t* rc_channels_scaled) -{ - return mavlink_msg_rc_channels_scaled_pack_chan(system_id, component_id, chan, msg, rc_channels_scaled->time_boot_ms, rc_channels_scaled->port, rc_channels_scaled->chan1_scaled, rc_channels_scaled->chan2_scaled, rc_channels_scaled->chan3_scaled, rc_channels_scaled->chan4_scaled, rc_channels_scaled->chan5_scaled, rc_channels_scaled->chan6_scaled, rc_channels_scaled->chan7_scaled, rc_channels_scaled->chan8_scaled, rc_channels_scaled->rssi); -} - -/** - * @brief Send a rc_channels_scaled message - * @param chan MAVLink channel to send the message - * - * @param time_boot_ms [ms] Timestamp (time since system boot). - * @param port Servo output port (set of 8 outputs = 1 port). Flight stacks running on Pixhawk should use: 0 = MAIN, 1 = AUX. - * @param chan1_scaled RC channel 1 value scaled. - * @param chan2_scaled RC channel 2 value scaled. - * @param chan3_scaled RC channel 3 value scaled. - * @param chan4_scaled RC channel 4 value scaled. - * @param chan5_scaled RC channel 5 value scaled. - * @param chan6_scaled RC channel 6 value scaled. - * @param chan7_scaled RC channel 7 value scaled. - * @param chan8_scaled RC channel 8 value scaled. - * @param rssi Receive signal strength indicator in device-dependent units/scale. Values: [0-254], UINT8_MAX: invalid/unknown. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_rc_channels_scaled_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t port, int16_t chan1_scaled, int16_t chan2_scaled, int16_t chan3_scaled, int16_t chan4_scaled, int16_t chan5_scaled, int16_t chan6_scaled, int16_t chan7_scaled, int16_t chan8_scaled, uint8_t rssi) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_int16_t(buf, 4, chan1_scaled); - _mav_put_int16_t(buf, 6, chan2_scaled); - _mav_put_int16_t(buf, 8, chan3_scaled); - _mav_put_int16_t(buf, 10, chan4_scaled); - _mav_put_int16_t(buf, 12, chan5_scaled); - _mav_put_int16_t(buf, 14, chan6_scaled); - _mav_put_int16_t(buf, 16, chan7_scaled); - _mav_put_int16_t(buf, 18, chan8_scaled); - _mav_put_uint8_t(buf, 20, port); - _mav_put_uint8_t(buf, 21, rssi); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_SCALED, buf, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_MIN_LEN, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_CRC); -#else - mavlink_rc_channels_scaled_t packet; - packet.time_boot_ms = time_boot_ms; - packet.chan1_scaled = chan1_scaled; - packet.chan2_scaled = chan2_scaled; - packet.chan3_scaled = chan3_scaled; - packet.chan4_scaled = chan4_scaled; - packet.chan5_scaled = chan5_scaled; - packet.chan6_scaled = chan6_scaled; - packet.chan7_scaled = chan7_scaled; - packet.chan8_scaled = chan8_scaled; - packet.port = port; - packet.rssi = rssi; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_SCALED, (const char *)&packet, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_MIN_LEN, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_CRC); -#endif -} - -/** - * @brief Send a rc_channels_scaled message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_rc_channels_scaled_send_struct(mavlink_channel_t chan, const mavlink_rc_channels_scaled_t* rc_channels_scaled) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_rc_channels_scaled_send(chan, rc_channels_scaled->time_boot_ms, rc_channels_scaled->port, rc_channels_scaled->chan1_scaled, rc_channels_scaled->chan2_scaled, rc_channels_scaled->chan3_scaled, rc_channels_scaled->chan4_scaled, rc_channels_scaled->chan5_scaled, rc_channels_scaled->chan6_scaled, rc_channels_scaled->chan7_scaled, rc_channels_scaled->chan8_scaled, rc_channels_scaled->rssi); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_SCALED, (const char *)rc_channels_scaled, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_MIN_LEN, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_CRC); -#endif -} - -#if MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_rc_channels_scaled_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t port, int16_t chan1_scaled, int16_t chan2_scaled, int16_t chan3_scaled, int16_t chan4_scaled, int16_t chan5_scaled, int16_t chan6_scaled, int16_t chan7_scaled, int16_t chan8_scaled, uint8_t rssi) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_int16_t(buf, 4, chan1_scaled); - _mav_put_int16_t(buf, 6, chan2_scaled); - _mav_put_int16_t(buf, 8, chan3_scaled); - _mav_put_int16_t(buf, 10, chan4_scaled); - _mav_put_int16_t(buf, 12, chan5_scaled); - _mav_put_int16_t(buf, 14, chan6_scaled); - _mav_put_int16_t(buf, 16, chan7_scaled); - _mav_put_int16_t(buf, 18, chan8_scaled); - _mav_put_uint8_t(buf, 20, port); - _mav_put_uint8_t(buf, 21, rssi); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_SCALED, buf, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_MIN_LEN, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_CRC); -#else - mavlink_rc_channels_scaled_t *packet = (mavlink_rc_channels_scaled_t *)msgbuf; - packet->time_boot_ms = time_boot_ms; - packet->chan1_scaled = chan1_scaled; - packet->chan2_scaled = chan2_scaled; - packet->chan3_scaled = chan3_scaled; - packet->chan4_scaled = chan4_scaled; - packet->chan5_scaled = chan5_scaled; - packet->chan6_scaled = chan6_scaled; - packet->chan7_scaled = chan7_scaled; - packet->chan8_scaled = chan8_scaled; - packet->port = port; - packet->rssi = rssi; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_SCALED, (const char *)packet, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_MIN_LEN, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_CRC); -#endif -} -#endif - -#endif - -// MESSAGE RC_CHANNELS_SCALED UNPACKING - - -/** - * @brief Get field time_boot_ms from rc_channels_scaled message - * - * @return [ms] Timestamp (time since system boot). - */ -static inline uint32_t mavlink_msg_rc_channels_scaled_get_time_boot_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field port from rc_channels_scaled message - * - * @return Servo output port (set of 8 outputs = 1 port). Flight stacks running on Pixhawk should use: 0 = MAIN, 1 = AUX. - */ -static inline uint8_t mavlink_msg_rc_channels_scaled_get_port(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 20); -} - -/** - * @brief Get field chan1_scaled from rc_channels_scaled message - * - * @return RC channel 1 value scaled. - */ -static inline int16_t mavlink_msg_rc_channels_scaled_get_chan1_scaled(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 4); -} - -/** - * @brief Get field chan2_scaled from rc_channels_scaled message - * - * @return RC channel 2 value scaled. - */ -static inline int16_t mavlink_msg_rc_channels_scaled_get_chan2_scaled(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 6); -} - -/** - * @brief Get field chan3_scaled from rc_channels_scaled message - * - * @return RC channel 3 value scaled. - */ -static inline int16_t mavlink_msg_rc_channels_scaled_get_chan3_scaled(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 8); -} - -/** - * @brief Get field chan4_scaled from rc_channels_scaled message - * - * @return RC channel 4 value scaled. - */ -static inline int16_t mavlink_msg_rc_channels_scaled_get_chan4_scaled(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 10); -} - -/** - * @brief Get field chan5_scaled from rc_channels_scaled message - * - * @return RC channel 5 value scaled. - */ -static inline int16_t mavlink_msg_rc_channels_scaled_get_chan5_scaled(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 12); -} - -/** - * @brief Get field chan6_scaled from rc_channels_scaled message - * - * @return RC channel 6 value scaled. - */ -static inline int16_t mavlink_msg_rc_channels_scaled_get_chan6_scaled(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 14); -} - -/** - * @brief Get field chan7_scaled from rc_channels_scaled message - * - * @return RC channel 7 value scaled. - */ -static inline int16_t mavlink_msg_rc_channels_scaled_get_chan7_scaled(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 16); -} - -/** - * @brief Get field chan8_scaled from rc_channels_scaled message - * - * @return RC channel 8 value scaled. - */ -static inline int16_t mavlink_msg_rc_channels_scaled_get_chan8_scaled(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 18); -} - -/** - * @brief Get field rssi from rc_channels_scaled message - * - * @return Receive signal strength indicator in device-dependent units/scale. Values: [0-254], UINT8_MAX: invalid/unknown. - */ -static inline uint8_t mavlink_msg_rc_channels_scaled_get_rssi(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 21); -} - -/** - * @brief Decode a rc_channels_scaled message into a struct - * - * @param msg The message to decode - * @param rc_channels_scaled C-struct to decode the message contents into - */ -static inline void mavlink_msg_rc_channels_scaled_decode(const mavlink_message_t* msg, mavlink_rc_channels_scaled_t* rc_channels_scaled) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - rc_channels_scaled->time_boot_ms = mavlink_msg_rc_channels_scaled_get_time_boot_ms(msg); - rc_channels_scaled->chan1_scaled = mavlink_msg_rc_channels_scaled_get_chan1_scaled(msg); - rc_channels_scaled->chan2_scaled = mavlink_msg_rc_channels_scaled_get_chan2_scaled(msg); - rc_channels_scaled->chan3_scaled = mavlink_msg_rc_channels_scaled_get_chan3_scaled(msg); - rc_channels_scaled->chan4_scaled = mavlink_msg_rc_channels_scaled_get_chan4_scaled(msg); - rc_channels_scaled->chan5_scaled = mavlink_msg_rc_channels_scaled_get_chan5_scaled(msg); - rc_channels_scaled->chan6_scaled = mavlink_msg_rc_channels_scaled_get_chan6_scaled(msg); - rc_channels_scaled->chan7_scaled = mavlink_msg_rc_channels_scaled_get_chan7_scaled(msg); - rc_channels_scaled->chan8_scaled = mavlink_msg_rc_channels_scaled_get_chan8_scaled(msg); - rc_channels_scaled->port = mavlink_msg_rc_channels_scaled_get_port(msg); - rc_channels_scaled->rssi = mavlink_msg_rc_channels_scaled_get_rssi(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN? msg->len : MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN; - memset(rc_channels_scaled, 0, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN); - memcpy(rc_channels_scaled, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_request_data_stream.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_request_data_stream.h deleted file mode 100644 index 617d61c6..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_request_data_stream.h +++ /dev/null @@ -1,313 +0,0 @@ -#pragma once -// MESSAGE REQUEST_DATA_STREAM PACKING - -#define MAVLINK_MSG_ID_REQUEST_DATA_STREAM 66 - - -typedef struct __mavlink_request_data_stream_t { - uint16_t req_message_rate; /*< [Hz] The requested message rate*/ - uint8_t target_system; /*< The target requested to send the message stream.*/ - uint8_t target_component; /*< The target requested to send the message stream.*/ - uint8_t req_stream_id; /*< The ID of the requested data stream*/ - uint8_t start_stop; /*< 1 to start sending, 0 to stop sending.*/ -} mavlink_request_data_stream_t; - -#define MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN 6 -#define MAVLINK_MSG_ID_REQUEST_DATA_STREAM_MIN_LEN 6 -#define MAVLINK_MSG_ID_66_LEN 6 -#define MAVLINK_MSG_ID_66_MIN_LEN 6 - -#define MAVLINK_MSG_ID_REQUEST_DATA_STREAM_CRC 148 -#define MAVLINK_MSG_ID_66_CRC 148 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_REQUEST_DATA_STREAM { \ - 66, \ - "REQUEST_DATA_STREAM", \ - 5, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_request_data_stream_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_request_data_stream_t, target_component) }, \ - { "req_stream_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_request_data_stream_t, req_stream_id) }, \ - { "req_message_rate", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_request_data_stream_t, req_message_rate) }, \ - { "start_stop", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_request_data_stream_t, start_stop) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_REQUEST_DATA_STREAM { \ - "REQUEST_DATA_STREAM", \ - 5, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_request_data_stream_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_request_data_stream_t, target_component) }, \ - { "req_stream_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_request_data_stream_t, req_stream_id) }, \ - { "req_message_rate", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_request_data_stream_t, req_message_rate) }, \ - { "start_stop", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_request_data_stream_t, start_stop) }, \ - } \ -} -#endif - -/** - * @brief Pack a request_data_stream message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system The target requested to send the message stream. - * @param target_component The target requested to send the message stream. - * @param req_stream_id The ID of the requested data stream - * @param req_message_rate [Hz] The requested message rate - * @param start_stop 1 to start sending, 0 to stop sending. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_request_data_stream_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component, uint8_t req_stream_id, uint16_t req_message_rate, uint8_t start_stop) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN]; - _mav_put_uint16_t(buf, 0, req_message_rate); - _mav_put_uint8_t(buf, 2, target_system); - _mav_put_uint8_t(buf, 3, target_component); - _mav_put_uint8_t(buf, 4, req_stream_id); - _mav_put_uint8_t(buf, 5, start_stop); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN); -#else - mavlink_request_data_stream_t packet; - packet.req_message_rate = req_message_rate; - packet.target_system = target_system; - packet.target_component = target_component; - packet.req_stream_id = req_stream_id; - packet.start_stop = start_stop; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_REQUEST_DATA_STREAM; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_MIN_LEN, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_CRC); -} - -/** - * @brief Pack a request_data_stream message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system The target requested to send the message stream. - * @param target_component The target requested to send the message stream. - * @param req_stream_id The ID of the requested data stream - * @param req_message_rate [Hz] The requested message rate - * @param start_stop 1 to start sending, 0 to stop sending. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_request_data_stream_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component,uint8_t req_stream_id,uint16_t req_message_rate,uint8_t start_stop) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN]; - _mav_put_uint16_t(buf, 0, req_message_rate); - _mav_put_uint8_t(buf, 2, target_system); - _mav_put_uint8_t(buf, 3, target_component); - _mav_put_uint8_t(buf, 4, req_stream_id); - _mav_put_uint8_t(buf, 5, start_stop); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN); -#else - mavlink_request_data_stream_t packet; - packet.req_message_rate = req_message_rate; - packet.target_system = target_system; - packet.target_component = target_component; - packet.req_stream_id = req_stream_id; - packet.start_stop = start_stop; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_REQUEST_DATA_STREAM; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_MIN_LEN, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_CRC); -} - -/** - * @brief Encode a request_data_stream struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param request_data_stream C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_request_data_stream_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_request_data_stream_t* request_data_stream) -{ - return mavlink_msg_request_data_stream_pack(system_id, component_id, msg, request_data_stream->target_system, request_data_stream->target_component, request_data_stream->req_stream_id, request_data_stream->req_message_rate, request_data_stream->start_stop); -} - -/** - * @brief Encode a request_data_stream struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param request_data_stream C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_request_data_stream_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_request_data_stream_t* request_data_stream) -{ - return mavlink_msg_request_data_stream_pack_chan(system_id, component_id, chan, msg, request_data_stream->target_system, request_data_stream->target_component, request_data_stream->req_stream_id, request_data_stream->req_message_rate, request_data_stream->start_stop); -} - -/** - * @brief Send a request_data_stream message - * @param chan MAVLink channel to send the message - * - * @param target_system The target requested to send the message stream. - * @param target_component The target requested to send the message stream. - * @param req_stream_id The ID of the requested data stream - * @param req_message_rate [Hz] The requested message rate - * @param start_stop 1 to start sending, 0 to stop sending. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_request_data_stream_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t req_stream_id, uint16_t req_message_rate, uint8_t start_stop) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN]; - _mav_put_uint16_t(buf, 0, req_message_rate); - _mav_put_uint8_t(buf, 2, target_system); - _mav_put_uint8_t(buf, 3, target_component); - _mav_put_uint8_t(buf, 4, req_stream_id); - _mav_put_uint8_t(buf, 5, start_stop); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_REQUEST_DATA_STREAM, buf, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_MIN_LEN, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_CRC); -#else - mavlink_request_data_stream_t packet; - packet.req_message_rate = req_message_rate; - packet.target_system = target_system; - packet.target_component = target_component; - packet.req_stream_id = req_stream_id; - packet.start_stop = start_stop; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_REQUEST_DATA_STREAM, (const char *)&packet, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_MIN_LEN, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_CRC); -#endif -} - -/** - * @brief Send a request_data_stream message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_request_data_stream_send_struct(mavlink_channel_t chan, const mavlink_request_data_stream_t* request_data_stream) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_request_data_stream_send(chan, request_data_stream->target_system, request_data_stream->target_component, request_data_stream->req_stream_id, request_data_stream->req_message_rate, request_data_stream->start_stop); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_REQUEST_DATA_STREAM, (const char *)request_data_stream, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_MIN_LEN, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_CRC); -#endif -} - -#if MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_request_data_stream_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t req_stream_id, uint16_t req_message_rate, uint8_t start_stop) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint16_t(buf, 0, req_message_rate); - _mav_put_uint8_t(buf, 2, target_system); - _mav_put_uint8_t(buf, 3, target_component); - _mav_put_uint8_t(buf, 4, req_stream_id); - _mav_put_uint8_t(buf, 5, start_stop); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_REQUEST_DATA_STREAM, buf, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_MIN_LEN, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_CRC); -#else - mavlink_request_data_stream_t *packet = (mavlink_request_data_stream_t *)msgbuf; - packet->req_message_rate = req_message_rate; - packet->target_system = target_system; - packet->target_component = target_component; - packet->req_stream_id = req_stream_id; - packet->start_stop = start_stop; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_REQUEST_DATA_STREAM, (const char *)packet, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_MIN_LEN, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_CRC); -#endif -} -#endif - -#endif - -// MESSAGE REQUEST_DATA_STREAM UNPACKING - - -/** - * @brief Get field target_system from request_data_stream message - * - * @return The target requested to send the message stream. - */ -static inline uint8_t mavlink_msg_request_data_stream_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 2); -} - -/** - * @brief Get field target_component from request_data_stream message - * - * @return The target requested to send the message stream. - */ -static inline uint8_t mavlink_msg_request_data_stream_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 3); -} - -/** - * @brief Get field req_stream_id from request_data_stream message - * - * @return The ID of the requested data stream - */ -static inline uint8_t mavlink_msg_request_data_stream_get_req_stream_id(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 4); -} - -/** - * @brief Get field req_message_rate from request_data_stream message - * - * @return [Hz] The requested message rate - */ -static inline uint16_t mavlink_msg_request_data_stream_get_req_message_rate(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 0); -} - -/** - * @brief Get field start_stop from request_data_stream message - * - * @return 1 to start sending, 0 to stop sending. - */ -static inline uint8_t mavlink_msg_request_data_stream_get_start_stop(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 5); -} - -/** - * @brief Decode a request_data_stream message into a struct - * - * @param msg The message to decode - * @param request_data_stream C-struct to decode the message contents into - */ -static inline void mavlink_msg_request_data_stream_decode(const mavlink_message_t* msg, mavlink_request_data_stream_t* request_data_stream) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - request_data_stream->req_message_rate = mavlink_msg_request_data_stream_get_req_message_rate(msg); - request_data_stream->target_system = mavlink_msg_request_data_stream_get_target_system(msg); - request_data_stream->target_component = mavlink_msg_request_data_stream_get_target_component(msg); - request_data_stream->req_stream_id = mavlink_msg_request_data_stream_get_req_stream_id(msg); - request_data_stream->start_stop = mavlink_msg_request_data_stream_get_start_stop(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN? msg->len : MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN; - memset(request_data_stream, 0, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN); - memcpy(request_data_stream, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_request_event.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_request_event.h deleted file mode 100644 index dcf15917..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_request_event.h +++ /dev/null @@ -1,288 +0,0 @@ -#pragma once -// MESSAGE REQUEST_EVENT PACKING - -#define MAVLINK_MSG_ID_REQUEST_EVENT 412 - - -typedef struct __mavlink_request_event_t { - uint16_t first_sequence; /*< First sequence number of the requested event.*/ - uint16_t last_sequence; /*< Last sequence number of the requested event.*/ - uint8_t target_system; /*< System ID*/ - uint8_t target_component; /*< Component ID*/ -} mavlink_request_event_t; - -#define MAVLINK_MSG_ID_REQUEST_EVENT_LEN 6 -#define MAVLINK_MSG_ID_REQUEST_EVENT_MIN_LEN 6 -#define MAVLINK_MSG_ID_412_LEN 6 -#define MAVLINK_MSG_ID_412_MIN_LEN 6 - -#define MAVLINK_MSG_ID_REQUEST_EVENT_CRC 33 -#define MAVLINK_MSG_ID_412_CRC 33 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_REQUEST_EVENT { \ - 412, \ - "REQUEST_EVENT", \ - 4, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_request_event_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_request_event_t, target_component) }, \ - { "first_sequence", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_request_event_t, first_sequence) }, \ - { "last_sequence", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_request_event_t, last_sequence) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_REQUEST_EVENT { \ - "REQUEST_EVENT", \ - 4, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_request_event_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_request_event_t, target_component) }, \ - { "first_sequence", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_request_event_t, first_sequence) }, \ - { "last_sequence", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_request_event_t, last_sequence) }, \ - } \ -} -#endif - -/** - * @brief Pack a request_event message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID - * @param target_component Component ID - * @param first_sequence First sequence number of the requested event. - * @param last_sequence Last sequence number of the requested event. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_request_event_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component, uint16_t first_sequence, uint16_t last_sequence) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_REQUEST_EVENT_LEN]; - _mav_put_uint16_t(buf, 0, first_sequence); - _mav_put_uint16_t(buf, 2, last_sequence); - _mav_put_uint8_t(buf, 4, target_system); - _mav_put_uint8_t(buf, 5, target_component); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_REQUEST_EVENT_LEN); -#else - mavlink_request_event_t packet; - packet.first_sequence = first_sequence; - packet.last_sequence = last_sequence; - packet.target_system = target_system; - packet.target_component = target_component; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_REQUEST_EVENT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_REQUEST_EVENT; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_REQUEST_EVENT_MIN_LEN, MAVLINK_MSG_ID_REQUEST_EVENT_LEN, MAVLINK_MSG_ID_REQUEST_EVENT_CRC); -} - -/** - * @brief Pack a request_event message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @param first_sequence First sequence number of the requested event. - * @param last_sequence Last sequence number of the requested event. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_request_event_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component,uint16_t first_sequence,uint16_t last_sequence) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_REQUEST_EVENT_LEN]; - _mav_put_uint16_t(buf, 0, first_sequence); - _mav_put_uint16_t(buf, 2, last_sequence); - _mav_put_uint8_t(buf, 4, target_system); - _mav_put_uint8_t(buf, 5, target_component); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_REQUEST_EVENT_LEN); -#else - mavlink_request_event_t packet; - packet.first_sequence = first_sequence; - packet.last_sequence = last_sequence; - packet.target_system = target_system; - packet.target_component = target_component; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_REQUEST_EVENT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_REQUEST_EVENT; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_REQUEST_EVENT_MIN_LEN, MAVLINK_MSG_ID_REQUEST_EVENT_LEN, MAVLINK_MSG_ID_REQUEST_EVENT_CRC); -} - -/** - * @brief Encode a request_event struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param request_event C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_request_event_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_request_event_t* request_event) -{ - return mavlink_msg_request_event_pack(system_id, component_id, msg, request_event->target_system, request_event->target_component, request_event->first_sequence, request_event->last_sequence); -} - -/** - * @brief Encode a request_event struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param request_event C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_request_event_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_request_event_t* request_event) -{ - return mavlink_msg_request_event_pack_chan(system_id, component_id, chan, msg, request_event->target_system, request_event->target_component, request_event->first_sequence, request_event->last_sequence); -} - -/** - * @brief Send a request_event message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param target_component Component ID - * @param first_sequence First sequence number of the requested event. - * @param last_sequence Last sequence number of the requested event. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_request_event_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t first_sequence, uint16_t last_sequence) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_REQUEST_EVENT_LEN]; - _mav_put_uint16_t(buf, 0, first_sequence); - _mav_put_uint16_t(buf, 2, last_sequence); - _mav_put_uint8_t(buf, 4, target_system); - _mav_put_uint8_t(buf, 5, target_component); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_REQUEST_EVENT, buf, MAVLINK_MSG_ID_REQUEST_EVENT_MIN_LEN, MAVLINK_MSG_ID_REQUEST_EVENT_LEN, MAVLINK_MSG_ID_REQUEST_EVENT_CRC); -#else - mavlink_request_event_t packet; - packet.first_sequence = first_sequence; - packet.last_sequence = last_sequence; - packet.target_system = target_system; - packet.target_component = target_component; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_REQUEST_EVENT, (const char *)&packet, MAVLINK_MSG_ID_REQUEST_EVENT_MIN_LEN, MAVLINK_MSG_ID_REQUEST_EVENT_LEN, MAVLINK_MSG_ID_REQUEST_EVENT_CRC); -#endif -} - -/** - * @brief Send a request_event message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_request_event_send_struct(mavlink_channel_t chan, const mavlink_request_event_t* request_event) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_request_event_send(chan, request_event->target_system, request_event->target_component, request_event->first_sequence, request_event->last_sequence); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_REQUEST_EVENT, (const char *)request_event, MAVLINK_MSG_ID_REQUEST_EVENT_MIN_LEN, MAVLINK_MSG_ID_REQUEST_EVENT_LEN, MAVLINK_MSG_ID_REQUEST_EVENT_CRC); -#endif -} - -#if MAVLINK_MSG_ID_REQUEST_EVENT_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_request_event_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t first_sequence, uint16_t last_sequence) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint16_t(buf, 0, first_sequence); - _mav_put_uint16_t(buf, 2, last_sequence); - _mav_put_uint8_t(buf, 4, target_system); - _mav_put_uint8_t(buf, 5, target_component); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_REQUEST_EVENT, buf, MAVLINK_MSG_ID_REQUEST_EVENT_MIN_LEN, MAVLINK_MSG_ID_REQUEST_EVENT_LEN, MAVLINK_MSG_ID_REQUEST_EVENT_CRC); -#else - mavlink_request_event_t *packet = (mavlink_request_event_t *)msgbuf; - packet->first_sequence = first_sequence; - packet->last_sequence = last_sequence; - packet->target_system = target_system; - packet->target_component = target_component; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_REQUEST_EVENT, (const char *)packet, MAVLINK_MSG_ID_REQUEST_EVENT_MIN_LEN, MAVLINK_MSG_ID_REQUEST_EVENT_LEN, MAVLINK_MSG_ID_REQUEST_EVENT_CRC); -#endif -} -#endif - -#endif - -// MESSAGE REQUEST_EVENT UNPACKING - - -/** - * @brief Get field target_system from request_event message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_request_event_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 4); -} - -/** - * @brief Get field target_component from request_event message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_request_event_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 5); -} - -/** - * @brief Get field first_sequence from request_event message - * - * @return First sequence number of the requested event. - */ -static inline uint16_t mavlink_msg_request_event_get_first_sequence(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 0); -} - -/** - * @brief Get field last_sequence from request_event message - * - * @return Last sequence number of the requested event. - */ -static inline uint16_t mavlink_msg_request_event_get_last_sequence(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 2); -} - -/** - * @brief Decode a request_event message into a struct - * - * @param msg The message to decode - * @param request_event C-struct to decode the message contents into - */ -static inline void mavlink_msg_request_event_decode(const mavlink_message_t* msg, mavlink_request_event_t* request_event) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - request_event->first_sequence = mavlink_msg_request_event_get_first_sequence(msg); - request_event->last_sequence = mavlink_msg_request_event_get_last_sequence(msg); - request_event->target_system = mavlink_msg_request_event_get_target_system(msg); - request_event->target_component = mavlink_msg_request_event_get_target_component(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_REQUEST_EVENT_LEN? msg->len : MAVLINK_MSG_ID_REQUEST_EVENT_LEN; - memset(request_event, 0, MAVLINK_MSG_ID_REQUEST_EVENT_LEN); - memcpy(request_event, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_resource_request.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_resource_request.h deleted file mode 100644 index 31c07f1a..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_resource_request.h +++ /dev/null @@ -1,306 +0,0 @@ -#pragma once -// MESSAGE RESOURCE_REQUEST PACKING - -#define MAVLINK_MSG_ID_RESOURCE_REQUEST 142 - - -typedef struct __mavlink_resource_request_t { - uint8_t request_id; /*< Request ID. This ID should be re-used when sending back URI contents*/ - uint8_t uri_type; /*< The type of requested URI. 0 = a file via URL. 1 = a UAVCAN binary*/ - uint8_t uri[120]; /*< The requested unique resource identifier (URI). It is not necessarily a straight domain name (depends on the URI type enum)*/ - uint8_t transfer_type; /*< The way the autopilot wants to receive the URI. 0 = MAVLink FTP. 1 = binary stream.*/ - uint8_t storage[120]; /*< The storage path the autopilot wants the URI to be stored in. Will only be valid if the transfer_type has a storage associated (e.g. MAVLink FTP).*/ -} mavlink_resource_request_t; - -#define MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN 243 -#define MAVLINK_MSG_ID_RESOURCE_REQUEST_MIN_LEN 243 -#define MAVLINK_MSG_ID_142_LEN 243 -#define MAVLINK_MSG_ID_142_MIN_LEN 243 - -#define MAVLINK_MSG_ID_RESOURCE_REQUEST_CRC 72 -#define MAVLINK_MSG_ID_142_CRC 72 - -#define MAVLINK_MSG_RESOURCE_REQUEST_FIELD_URI_LEN 120 -#define MAVLINK_MSG_RESOURCE_REQUEST_FIELD_STORAGE_LEN 120 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_RESOURCE_REQUEST { \ - 142, \ - "RESOURCE_REQUEST", \ - 5, \ - { { "request_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_resource_request_t, request_id) }, \ - { "uri_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_resource_request_t, uri_type) }, \ - { "uri", NULL, MAVLINK_TYPE_UINT8_T, 120, 2, offsetof(mavlink_resource_request_t, uri) }, \ - { "transfer_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 122, offsetof(mavlink_resource_request_t, transfer_type) }, \ - { "storage", NULL, MAVLINK_TYPE_UINT8_T, 120, 123, offsetof(mavlink_resource_request_t, storage) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_RESOURCE_REQUEST { \ - "RESOURCE_REQUEST", \ - 5, \ - { { "request_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_resource_request_t, request_id) }, \ - { "uri_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_resource_request_t, uri_type) }, \ - { "uri", NULL, MAVLINK_TYPE_UINT8_T, 120, 2, offsetof(mavlink_resource_request_t, uri) }, \ - { "transfer_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 122, offsetof(mavlink_resource_request_t, transfer_type) }, \ - { "storage", NULL, MAVLINK_TYPE_UINT8_T, 120, 123, offsetof(mavlink_resource_request_t, storage) }, \ - } \ -} -#endif - -/** - * @brief Pack a resource_request message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param request_id Request ID. This ID should be re-used when sending back URI contents - * @param uri_type The type of requested URI. 0 = a file via URL. 1 = a UAVCAN binary - * @param uri The requested unique resource identifier (URI). It is not necessarily a straight domain name (depends on the URI type enum) - * @param transfer_type The way the autopilot wants to receive the URI. 0 = MAVLink FTP. 1 = binary stream. - * @param storage The storage path the autopilot wants the URI to be stored in. Will only be valid if the transfer_type has a storage associated (e.g. MAVLink FTP). - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_resource_request_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t request_id, uint8_t uri_type, const uint8_t *uri, uint8_t transfer_type, const uint8_t *storage) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN]; - _mav_put_uint8_t(buf, 0, request_id); - _mav_put_uint8_t(buf, 1, uri_type); - _mav_put_uint8_t(buf, 122, transfer_type); - _mav_put_uint8_t_array(buf, 2, uri, 120); - _mav_put_uint8_t_array(buf, 123, storage, 120); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN); -#else - mavlink_resource_request_t packet; - packet.request_id = request_id; - packet.uri_type = uri_type; - packet.transfer_type = transfer_type; - mav_array_memcpy(packet.uri, uri, sizeof(uint8_t)*120); - mav_array_memcpy(packet.storage, storage, sizeof(uint8_t)*120); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_RESOURCE_REQUEST; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RESOURCE_REQUEST_MIN_LEN, MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN, MAVLINK_MSG_ID_RESOURCE_REQUEST_CRC); -} - -/** - * @brief Pack a resource_request message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param request_id Request ID. This ID should be re-used when sending back URI contents - * @param uri_type The type of requested URI. 0 = a file via URL. 1 = a UAVCAN binary - * @param uri The requested unique resource identifier (URI). It is not necessarily a straight domain name (depends on the URI type enum) - * @param transfer_type The way the autopilot wants to receive the URI. 0 = MAVLink FTP. 1 = binary stream. - * @param storage The storage path the autopilot wants the URI to be stored in. Will only be valid if the transfer_type has a storage associated (e.g. MAVLink FTP). - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_resource_request_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t request_id,uint8_t uri_type,const uint8_t *uri,uint8_t transfer_type,const uint8_t *storage) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN]; - _mav_put_uint8_t(buf, 0, request_id); - _mav_put_uint8_t(buf, 1, uri_type); - _mav_put_uint8_t(buf, 122, transfer_type); - _mav_put_uint8_t_array(buf, 2, uri, 120); - _mav_put_uint8_t_array(buf, 123, storage, 120); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN); -#else - mavlink_resource_request_t packet; - packet.request_id = request_id; - packet.uri_type = uri_type; - packet.transfer_type = transfer_type; - mav_array_memcpy(packet.uri, uri, sizeof(uint8_t)*120); - mav_array_memcpy(packet.storage, storage, sizeof(uint8_t)*120); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_RESOURCE_REQUEST; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RESOURCE_REQUEST_MIN_LEN, MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN, MAVLINK_MSG_ID_RESOURCE_REQUEST_CRC); -} - -/** - * @brief Encode a resource_request struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param resource_request C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_resource_request_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_resource_request_t* resource_request) -{ - return mavlink_msg_resource_request_pack(system_id, component_id, msg, resource_request->request_id, resource_request->uri_type, resource_request->uri, resource_request->transfer_type, resource_request->storage); -} - -/** - * @brief Encode a resource_request struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param resource_request C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_resource_request_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_resource_request_t* resource_request) -{ - return mavlink_msg_resource_request_pack_chan(system_id, component_id, chan, msg, resource_request->request_id, resource_request->uri_type, resource_request->uri, resource_request->transfer_type, resource_request->storage); -} - -/** - * @brief Send a resource_request message - * @param chan MAVLink channel to send the message - * - * @param request_id Request ID. This ID should be re-used when sending back URI contents - * @param uri_type The type of requested URI. 0 = a file via URL. 1 = a UAVCAN binary - * @param uri The requested unique resource identifier (URI). It is not necessarily a straight domain name (depends on the URI type enum) - * @param transfer_type The way the autopilot wants to receive the URI. 0 = MAVLink FTP. 1 = binary stream. - * @param storage The storage path the autopilot wants the URI to be stored in. Will only be valid if the transfer_type has a storage associated (e.g. MAVLink FTP). - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_resource_request_send(mavlink_channel_t chan, uint8_t request_id, uint8_t uri_type, const uint8_t *uri, uint8_t transfer_type, const uint8_t *storage) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN]; - _mav_put_uint8_t(buf, 0, request_id); - _mav_put_uint8_t(buf, 1, uri_type); - _mav_put_uint8_t(buf, 122, transfer_type); - _mav_put_uint8_t_array(buf, 2, uri, 120); - _mav_put_uint8_t_array(buf, 123, storage, 120); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RESOURCE_REQUEST, buf, MAVLINK_MSG_ID_RESOURCE_REQUEST_MIN_LEN, MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN, MAVLINK_MSG_ID_RESOURCE_REQUEST_CRC); -#else - mavlink_resource_request_t packet; - packet.request_id = request_id; - packet.uri_type = uri_type; - packet.transfer_type = transfer_type; - mav_array_memcpy(packet.uri, uri, sizeof(uint8_t)*120); - mav_array_memcpy(packet.storage, storage, sizeof(uint8_t)*120); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RESOURCE_REQUEST, (const char *)&packet, MAVLINK_MSG_ID_RESOURCE_REQUEST_MIN_LEN, MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN, MAVLINK_MSG_ID_RESOURCE_REQUEST_CRC); -#endif -} - -/** - * @brief Send a resource_request message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_resource_request_send_struct(mavlink_channel_t chan, const mavlink_resource_request_t* resource_request) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_resource_request_send(chan, resource_request->request_id, resource_request->uri_type, resource_request->uri, resource_request->transfer_type, resource_request->storage); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RESOURCE_REQUEST, (const char *)resource_request, MAVLINK_MSG_ID_RESOURCE_REQUEST_MIN_LEN, MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN, MAVLINK_MSG_ID_RESOURCE_REQUEST_CRC); -#endif -} - -#if MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_resource_request_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t request_id, uint8_t uri_type, const uint8_t *uri, uint8_t transfer_type, const uint8_t *storage) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint8_t(buf, 0, request_id); - _mav_put_uint8_t(buf, 1, uri_type); - _mav_put_uint8_t(buf, 122, transfer_type); - _mav_put_uint8_t_array(buf, 2, uri, 120); - _mav_put_uint8_t_array(buf, 123, storage, 120); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RESOURCE_REQUEST, buf, MAVLINK_MSG_ID_RESOURCE_REQUEST_MIN_LEN, MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN, MAVLINK_MSG_ID_RESOURCE_REQUEST_CRC); -#else - mavlink_resource_request_t *packet = (mavlink_resource_request_t *)msgbuf; - packet->request_id = request_id; - packet->uri_type = uri_type; - packet->transfer_type = transfer_type; - mav_array_memcpy(packet->uri, uri, sizeof(uint8_t)*120); - mav_array_memcpy(packet->storage, storage, sizeof(uint8_t)*120); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RESOURCE_REQUEST, (const char *)packet, MAVLINK_MSG_ID_RESOURCE_REQUEST_MIN_LEN, MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN, MAVLINK_MSG_ID_RESOURCE_REQUEST_CRC); -#endif -} -#endif - -#endif - -// MESSAGE RESOURCE_REQUEST UNPACKING - - -/** - * @brief Get field request_id from resource_request message - * - * @return Request ID. This ID should be re-used when sending back URI contents - */ -static inline uint8_t mavlink_msg_resource_request_get_request_id(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 0); -} - -/** - * @brief Get field uri_type from resource_request message - * - * @return The type of requested URI. 0 = a file via URL. 1 = a UAVCAN binary - */ -static inline uint8_t mavlink_msg_resource_request_get_uri_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 1); -} - -/** - * @brief Get field uri from resource_request message - * - * @return The requested unique resource identifier (URI). It is not necessarily a straight domain name (depends on the URI type enum) - */ -static inline uint16_t mavlink_msg_resource_request_get_uri(const mavlink_message_t* msg, uint8_t *uri) -{ - return _MAV_RETURN_uint8_t_array(msg, uri, 120, 2); -} - -/** - * @brief Get field transfer_type from resource_request message - * - * @return The way the autopilot wants to receive the URI. 0 = MAVLink FTP. 1 = binary stream. - */ -static inline uint8_t mavlink_msg_resource_request_get_transfer_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 122); -} - -/** - * @brief Get field storage from resource_request message - * - * @return The storage path the autopilot wants the URI to be stored in. Will only be valid if the transfer_type has a storage associated (e.g. MAVLink FTP). - */ -static inline uint16_t mavlink_msg_resource_request_get_storage(const mavlink_message_t* msg, uint8_t *storage) -{ - return _MAV_RETURN_uint8_t_array(msg, storage, 120, 123); -} - -/** - * @brief Decode a resource_request message into a struct - * - * @param msg The message to decode - * @param resource_request C-struct to decode the message contents into - */ -static inline void mavlink_msg_resource_request_decode(const mavlink_message_t* msg, mavlink_resource_request_t* resource_request) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - resource_request->request_id = mavlink_msg_resource_request_get_request_id(msg); - resource_request->uri_type = mavlink_msg_resource_request_get_uri_type(msg); - mavlink_msg_resource_request_get_uri(msg, resource_request->uri); - resource_request->transfer_type = mavlink_msg_resource_request_get_transfer_type(msg); - mavlink_msg_resource_request_get_storage(msg, resource_request->storage); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN? msg->len : MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN; - memset(resource_request, 0, MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN); - memcpy(resource_request, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_response_event_error.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_response_event_error.h deleted file mode 100644 index 9b665a23..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_response_event_error.h +++ /dev/null @@ -1,313 +0,0 @@ -#pragma once -// MESSAGE RESPONSE_EVENT_ERROR PACKING - -#define MAVLINK_MSG_ID_RESPONSE_EVENT_ERROR 413 - - -typedef struct __mavlink_response_event_error_t { - uint16_t sequence; /*< Sequence number.*/ - uint16_t sequence_oldest_available; /*< Oldest Sequence number that is still available after the sequence set in REQUEST_EVENT.*/ - uint8_t target_system; /*< System ID*/ - uint8_t target_component; /*< Component ID*/ - uint8_t reason; /*< Error reason.*/ -} mavlink_response_event_error_t; - -#define MAVLINK_MSG_ID_RESPONSE_EVENT_ERROR_LEN 7 -#define MAVLINK_MSG_ID_RESPONSE_EVENT_ERROR_MIN_LEN 7 -#define MAVLINK_MSG_ID_413_LEN 7 -#define MAVLINK_MSG_ID_413_MIN_LEN 7 - -#define MAVLINK_MSG_ID_RESPONSE_EVENT_ERROR_CRC 77 -#define MAVLINK_MSG_ID_413_CRC 77 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_RESPONSE_EVENT_ERROR { \ - 413, \ - "RESPONSE_EVENT_ERROR", \ - 5, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_response_event_error_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_response_event_error_t, target_component) }, \ - { "sequence", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_response_event_error_t, sequence) }, \ - { "sequence_oldest_available", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_response_event_error_t, sequence_oldest_available) }, \ - { "reason", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_response_event_error_t, reason) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_RESPONSE_EVENT_ERROR { \ - "RESPONSE_EVENT_ERROR", \ - 5, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_response_event_error_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_response_event_error_t, target_component) }, \ - { "sequence", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_response_event_error_t, sequence) }, \ - { "sequence_oldest_available", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_response_event_error_t, sequence_oldest_available) }, \ - { "reason", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_response_event_error_t, reason) }, \ - } \ -} -#endif - -/** - * @brief Pack a response_event_error message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID - * @param target_component Component ID - * @param sequence Sequence number. - * @param sequence_oldest_available Oldest Sequence number that is still available after the sequence set in REQUEST_EVENT. - * @param reason Error reason. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_response_event_error_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component, uint16_t sequence, uint16_t sequence_oldest_available, uint8_t reason) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_RESPONSE_EVENT_ERROR_LEN]; - _mav_put_uint16_t(buf, 0, sequence); - _mav_put_uint16_t(buf, 2, sequence_oldest_available); - _mav_put_uint8_t(buf, 4, target_system); - _mav_put_uint8_t(buf, 5, target_component); - _mav_put_uint8_t(buf, 6, reason); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RESPONSE_EVENT_ERROR_LEN); -#else - mavlink_response_event_error_t packet; - packet.sequence = sequence; - packet.sequence_oldest_available = sequence_oldest_available; - packet.target_system = target_system; - packet.target_component = target_component; - packet.reason = reason; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RESPONSE_EVENT_ERROR_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_RESPONSE_EVENT_ERROR; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RESPONSE_EVENT_ERROR_MIN_LEN, MAVLINK_MSG_ID_RESPONSE_EVENT_ERROR_LEN, MAVLINK_MSG_ID_RESPONSE_EVENT_ERROR_CRC); -} - -/** - * @brief Pack a response_event_error message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @param sequence Sequence number. - * @param sequence_oldest_available Oldest Sequence number that is still available after the sequence set in REQUEST_EVENT. - * @param reason Error reason. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_response_event_error_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component,uint16_t sequence,uint16_t sequence_oldest_available,uint8_t reason) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_RESPONSE_EVENT_ERROR_LEN]; - _mav_put_uint16_t(buf, 0, sequence); - _mav_put_uint16_t(buf, 2, sequence_oldest_available); - _mav_put_uint8_t(buf, 4, target_system); - _mav_put_uint8_t(buf, 5, target_component); - _mav_put_uint8_t(buf, 6, reason); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RESPONSE_EVENT_ERROR_LEN); -#else - mavlink_response_event_error_t packet; - packet.sequence = sequence; - packet.sequence_oldest_available = sequence_oldest_available; - packet.target_system = target_system; - packet.target_component = target_component; - packet.reason = reason; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RESPONSE_EVENT_ERROR_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_RESPONSE_EVENT_ERROR; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RESPONSE_EVENT_ERROR_MIN_LEN, MAVLINK_MSG_ID_RESPONSE_EVENT_ERROR_LEN, MAVLINK_MSG_ID_RESPONSE_EVENT_ERROR_CRC); -} - -/** - * @brief Encode a response_event_error struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param response_event_error C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_response_event_error_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_response_event_error_t* response_event_error) -{ - return mavlink_msg_response_event_error_pack(system_id, component_id, msg, response_event_error->target_system, response_event_error->target_component, response_event_error->sequence, response_event_error->sequence_oldest_available, response_event_error->reason); -} - -/** - * @brief Encode a response_event_error struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param response_event_error C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_response_event_error_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_response_event_error_t* response_event_error) -{ - return mavlink_msg_response_event_error_pack_chan(system_id, component_id, chan, msg, response_event_error->target_system, response_event_error->target_component, response_event_error->sequence, response_event_error->sequence_oldest_available, response_event_error->reason); -} - -/** - * @brief Send a response_event_error message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param target_component Component ID - * @param sequence Sequence number. - * @param sequence_oldest_available Oldest Sequence number that is still available after the sequence set in REQUEST_EVENT. - * @param reason Error reason. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_response_event_error_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t sequence, uint16_t sequence_oldest_available, uint8_t reason) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_RESPONSE_EVENT_ERROR_LEN]; - _mav_put_uint16_t(buf, 0, sequence); - _mav_put_uint16_t(buf, 2, sequence_oldest_available); - _mav_put_uint8_t(buf, 4, target_system); - _mav_put_uint8_t(buf, 5, target_component); - _mav_put_uint8_t(buf, 6, reason); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RESPONSE_EVENT_ERROR, buf, MAVLINK_MSG_ID_RESPONSE_EVENT_ERROR_MIN_LEN, MAVLINK_MSG_ID_RESPONSE_EVENT_ERROR_LEN, MAVLINK_MSG_ID_RESPONSE_EVENT_ERROR_CRC); -#else - mavlink_response_event_error_t packet; - packet.sequence = sequence; - packet.sequence_oldest_available = sequence_oldest_available; - packet.target_system = target_system; - packet.target_component = target_component; - packet.reason = reason; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RESPONSE_EVENT_ERROR, (const char *)&packet, MAVLINK_MSG_ID_RESPONSE_EVENT_ERROR_MIN_LEN, MAVLINK_MSG_ID_RESPONSE_EVENT_ERROR_LEN, MAVLINK_MSG_ID_RESPONSE_EVENT_ERROR_CRC); -#endif -} - -/** - * @brief Send a response_event_error message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_response_event_error_send_struct(mavlink_channel_t chan, const mavlink_response_event_error_t* response_event_error) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_response_event_error_send(chan, response_event_error->target_system, response_event_error->target_component, response_event_error->sequence, response_event_error->sequence_oldest_available, response_event_error->reason); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RESPONSE_EVENT_ERROR, (const char *)response_event_error, MAVLINK_MSG_ID_RESPONSE_EVENT_ERROR_MIN_LEN, MAVLINK_MSG_ID_RESPONSE_EVENT_ERROR_LEN, MAVLINK_MSG_ID_RESPONSE_EVENT_ERROR_CRC); -#endif -} - -#if MAVLINK_MSG_ID_RESPONSE_EVENT_ERROR_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_response_event_error_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t sequence, uint16_t sequence_oldest_available, uint8_t reason) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint16_t(buf, 0, sequence); - _mav_put_uint16_t(buf, 2, sequence_oldest_available); - _mav_put_uint8_t(buf, 4, target_system); - _mav_put_uint8_t(buf, 5, target_component); - _mav_put_uint8_t(buf, 6, reason); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RESPONSE_EVENT_ERROR, buf, MAVLINK_MSG_ID_RESPONSE_EVENT_ERROR_MIN_LEN, MAVLINK_MSG_ID_RESPONSE_EVENT_ERROR_LEN, MAVLINK_MSG_ID_RESPONSE_EVENT_ERROR_CRC); -#else - mavlink_response_event_error_t *packet = (mavlink_response_event_error_t *)msgbuf; - packet->sequence = sequence; - packet->sequence_oldest_available = sequence_oldest_available; - packet->target_system = target_system; - packet->target_component = target_component; - packet->reason = reason; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RESPONSE_EVENT_ERROR, (const char *)packet, MAVLINK_MSG_ID_RESPONSE_EVENT_ERROR_MIN_LEN, MAVLINK_MSG_ID_RESPONSE_EVENT_ERROR_LEN, MAVLINK_MSG_ID_RESPONSE_EVENT_ERROR_CRC); -#endif -} -#endif - -#endif - -// MESSAGE RESPONSE_EVENT_ERROR UNPACKING - - -/** - * @brief Get field target_system from response_event_error message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_response_event_error_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 4); -} - -/** - * @brief Get field target_component from response_event_error message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_response_event_error_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 5); -} - -/** - * @brief Get field sequence from response_event_error message - * - * @return Sequence number. - */ -static inline uint16_t mavlink_msg_response_event_error_get_sequence(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 0); -} - -/** - * @brief Get field sequence_oldest_available from response_event_error message - * - * @return Oldest Sequence number that is still available after the sequence set in REQUEST_EVENT. - */ -static inline uint16_t mavlink_msg_response_event_error_get_sequence_oldest_available(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 2); -} - -/** - * @brief Get field reason from response_event_error message - * - * @return Error reason. - */ -static inline uint8_t mavlink_msg_response_event_error_get_reason(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 6); -} - -/** - * @brief Decode a response_event_error message into a struct - * - * @param msg The message to decode - * @param response_event_error C-struct to decode the message contents into - */ -static inline void mavlink_msg_response_event_error_decode(const mavlink_message_t* msg, mavlink_response_event_error_t* response_event_error) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - response_event_error->sequence = mavlink_msg_response_event_error_get_sequence(msg); - response_event_error->sequence_oldest_available = mavlink_msg_response_event_error_get_sequence_oldest_available(msg); - response_event_error->target_system = mavlink_msg_response_event_error_get_target_system(msg); - response_event_error->target_component = mavlink_msg_response_event_error_get_target_component(msg); - response_event_error->reason = mavlink_msg_response_event_error_get_reason(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_RESPONSE_EVENT_ERROR_LEN? msg->len : MAVLINK_MSG_ID_RESPONSE_EVENT_ERROR_LEN; - memset(response_event_error, 0, MAVLINK_MSG_ID_RESPONSE_EVENT_ERROR_LEN); - memcpy(response_event_error, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_safety_allowed_area.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_safety_allowed_area.h deleted file mode 100644 index 66b5c461..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_safety_allowed_area.h +++ /dev/null @@ -1,363 +0,0 @@ -#pragma once -// MESSAGE SAFETY_ALLOWED_AREA PACKING - -#define MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA 55 - - -typedef struct __mavlink_safety_allowed_area_t { - float p1x; /*< [m] x position 1 / Latitude 1*/ - float p1y; /*< [m] y position 1 / Longitude 1*/ - float p1z; /*< [m] z position 1 / Altitude 1*/ - float p2x; /*< [m] x position 2 / Latitude 2*/ - float p2y; /*< [m] y position 2 / Longitude 2*/ - float p2z; /*< [m] z position 2 / Altitude 2*/ - uint8_t frame; /*< Coordinate frame. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down.*/ -} mavlink_safety_allowed_area_t; - -#define MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN 25 -#define MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_MIN_LEN 25 -#define MAVLINK_MSG_ID_55_LEN 25 -#define MAVLINK_MSG_ID_55_MIN_LEN 25 - -#define MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_CRC 3 -#define MAVLINK_MSG_ID_55_CRC 3 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_SAFETY_ALLOWED_AREA { \ - 55, \ - "SAFETY_ALLOWED_AREA", \ - 7, \ - { { "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_safety_allowed_area_t, frame) }, \ - { "p1x", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_safety_allowed_area_t, p1x) }, \ - { "p1y", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_safety_allowed_area_t, p1y) }, \ - { "p1z", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_safety_allowed_area_t, p1z) }, \ - { "p2x", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_safety_allowed_area_t, p2x) }, \ - { "p2y", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_safety_allowed_area_t, p2y) }, \ - { "p2z", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_safety_allowed_area_t, p2z) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_SAFETY_ALLOWED_AREA { \ - "SAFETY_ALLOWED_AREA", \ - 7, \ - { { "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_safety_allowed_area_t, frame) }, \ - { "p1x", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_safety_allowed_area_t, p1x) }, \ - { "p1y", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_safety_allowed_area_t, p1y) }, \ - { "p1z", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_safety_allowed_area_t, p1z) }, \ - { "p2x", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_safety_allowed_area_t, p2x) }, \ - { "p2y", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_safety_allowed_area_t, p2y) }, \ - { "p2z", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_safety_allowed_area_t, p2z) }, \ - } \ -} -#endif - -/** - * @brief Pack a safety_allowed_area message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param frame Coordinate frame. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. - * @param p1x [m] x position 1 / Latitude 1 - * @param p1y [m] y position 1 / Longitude 1 - * @param p1z [m] z position 1 / Altitude 1 - * @param p2x [m] x position 2 / Latitude 2 - * @param p2y [m] y position 2 / Longitude 2 - * @param p2z [m] z position 2 / Altitude 2 - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_safety_allowed_area_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t frame, float p1x, float p1y, float p1z, float p2x, float p2y, float p2z) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN]; - _mav_put_float(buf, 0, p1x); - _mav_put_float(buf, 4, p1y); - _mav_put_float(buf, 8, p1z); - _mav_put_float(buf, 12, p2x); - _mav_put_float(buf, 16, p2y); - _mav_put_float(buf, 20, p2z); - _mav_put_uint8_t(buf, 24, frame); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN); -#else - mavlink_safety_allowed_area_t packet; - packet.p1x = p1x; - packet.p1y = p1y; - packet.p1z = p1z; - packet.p2x = p2x; - packet.p2y = p2y; - packet.p2z = p2z; - packet.frame = frame; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_MIN_LEN, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_CRC); -} - -/** - * @brief Pack a safety_allowed_area message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param frame Coordinate frame. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. - * @param p1x [m] x position 1 / Latitude 1 - * @param p1y [m] y position 1 / Longitude 1 - * @param p1z [m] z position 1 / Altitude 1 - * @param p2x [m] x position 2 / Latitude 2 - * @param p2y [m] y position 2 / Longitude 2 - * @param p2z [m] z position 2 / Altitude 2 - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_safety_allowed_area_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t frame,float p1x,float p1y,float p1z,float p2x,float p2y,float p2z) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN]; - _mav_put_float(buf, 0, p1x); - _mav_put_float(buf, 4, p1y); - _mav_put_float(buf, 8, p1z); - _mav_put_float(buf, 12, p2x); - _mav_put_float(buf, 16, p2y); - _mav_put_float(buf, 20, p2z); - _mav_put_uint8_t(buf, 24, frame); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN); -#else - mavlink_safety_allowed_area_t packet; - packet.p1x = p1x; - packet.p1y = p1y; - packet.p1z = p1z; - packet.p2x = p2x; - packet.p2y = p2y; - packet.p2z = p2z; - packet.frame = frame; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_MIN_LEN, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_CRC); -} - -/** - * @brief Encode a safety_allowed_area struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param safety_allowed_area C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_safety_allowed_area_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_safety_allowed_area_t* safety_allowed_area) -{ - return mavlink_msg_safety_allowed_area_pack(system_id, component_id, msg, safety_allowed_area->frame, safety_allowed_area->p1x, safety_allowed_area->p1y, safety_allowed_area->p1z, safety_allowed_area->p2x, safety_allowed_area->p2y, safety_allowed_area->p2z); -} - -/** - * @brief Encode a safety_allowed_area struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param safety_allowed_area C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_safety_allowed_area_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_safety_allowed_area_t* safety_allowed_area) -{ - return mavlink_msg_safety_allowed_area_pack_chan(system_id, component_id, chan, msg, safety_allowed_area->frame, safety_allowed_area->p1x, safety_allowed_area->p1y, safety_allowed_area->p1z, safety_allowed_area->p2x, safety_allowed_area->p2y, safety_allowed_area->p2z); -} - -/** - * @brief Send a safety_allowed_area message - * @param chan MAVLink channel to send the message - * - * @param frame Coordinate frame. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. - * @param p1x [m] x position 1 / Latitude 1 - * @param p1y [m] y position 1 / Longitude 1 - * @param p1z [m] z position 1 / Altitude 1 - * @param p2x [m] x position 2 / Latitude 2 - * @param p2y [m] y position 2 / Longitude 2 - * @param p2z [m] z position 2 / Altitude 2 - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_safety_allowed_area_send(mavlink_channel_t chan, uint8_t frame, float p1x, float p1y, float p1z, float p2x, float p2y, float p2z) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN]; - _mav_put_float(buf, 0, p1x); - _mav_put_float(buf, 4, p1y); - _mav_put_float(buf, 8, p1z); - _mav_put_float(buf, 12, p2x); - _mav_put_float(buf, 16, p2y); - _mav_put_float(buf, 20, p2z); - _mav_put_uint8_t(buf, 24, frame); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA, buf, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_MIN_LEN, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_CRC); -#else - mavlink_safety_allowed_area_t packet; - packet.p1x = p1x; - packet.p1y = p1y; - packet.p1z = p1z; - packet.p2x = p2x; - packet.p2y = p2y; - packet.p2z = p2z; - packet.frame = frame; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA, (const char *)&packet, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_MIN_LEN, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_CRC); -#endif -} - -/** - * @brief Send a safety_allowed_area message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_safety_allowed_area_send_struct(mavlink_channel_t chan, const mavlink_safety_allowed_area_t* safety_allowed_area) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_safety_allowed_area_send(chan, safety_allowed_area->frame, safety_allowed_area->p1x, safety_allowed_area->p1y, safety_allowed_area->p1z, safety_allowed_area->p2x, safety_allowed_area->p2y, safety_allowed_area->p2z); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA, (const char *)safety_allowed_area, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_MIN_LEN, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_CRC); -#endif -} - -#if MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_safety_allowed_area_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t frame, float p1x, float p1y, float p1z, float p2x, float p2y, float p2z) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_float(buf, 0, p1x); - _mav_put_float(buf, 4, p1y); - _mav_put_float(buf, 8, p1z); - _mav_put_float(buf, 12, p2x); - _mav_put_float(buf, 16, p2y); - _mav_put_float(buf, 20, p2z); - _mav_put_uint8_t(buf, 24, frame); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA, buf, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_MIN_LEN, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_CRC); -#else - mavlink_safety_allowed_area_t *packet = (mavlink_safety_allowed_area_t *)msgbuf; - packet->p1x = p1x; - packet->p1y = p1y; - packet->p1z = p1z; - packet->p2x = p2x; - packet->p2y = p2y; - packet->p2z = p2z; - packet->frame = frame; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA, (const char *)packet, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_MIN_LEN, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_CRC); -#endif -} -#endif - -#endif - -// MESSAGE SAFETY_ALLOWED_AREA UNPACKING - - -/** - * @brief Get field frame from safety_allowed_area message - * - * @return Coordinate frame. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. - */ -static inline uint8_t mavlink_msg_safety_allowed_area_get_frame(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 24); -} - -/** - * @brief Get field p1x from safety_allowed_area message - * - * @return [m] x position 1 / Latitude 1 - */ -static inline float mavlink_msg_safety_allowed_area_get_p1x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 0); -} - -/** - * @brief Get field p1y from safety_allowed_area message - * - * @return [m] y position 1 / Longitude 1 - */ -static inline float mavlink_msg_safety_allowed_area_get_p1y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 4); -} - -/** - * @brief Get field p1z from safety_allowed_area message - * - * @return [m] z position 1 / Altitude 1 - */ -static inline float mavlink_msg_safety_allowed_area_get_p1z(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field p2x from safety_allowed_area message - * - * @return [m] x position 2 / Latitude 2 - */ -static inline float mavlink_msg_safety_allowed_area_get_p2x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field p2y from safety_allowed_area message - * - * @return [m] y position 2 / Longitude 2 - */ -static inline float mavlink_msg_safety_allowed_area_get_p2y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field p2z from safety_allowed_area message - * - * @return [m] z position 2 / Altitude 2 - */ -static inline float mavlink_msg_safety_allowed_area_get_p2z(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Decode a safety_allowed_area message into a struct - * - * @param msg The message to decode - * @param safety_allowed_area C-struct to decode the message contents into - */ -static inline void mavlink_msg_safety_allowed_area_decode(const mavlink_message_t* msg, mavlink_safety_allowed_area_t* safety_allowed_area) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - safety_allowed_area->p1x = mavlink_msg_safety_allowed_area_get_p1x(msg); - safety_allowed_area->p1y = mavlink_msg_safety_allowed_area_get_p1y(msg); - safety_allowed_area->p1z = mavlink_msg_safety_allowed_area_get_p1z(msg); - safety_allowed_area->p2x = mavlink_msg_safety_allowed_area_get_p2x(msg); - safety_allowed_area->p2y = mavlink_msg_safety_allowed_area_get_p2y(msg); - safety_allowed_area->p2z = mavlink_msg_safety_allowed_area_get_p2z(msg); - safety_allowed_area->frame = mavlink_msg_safety_allowed_area_get_frame(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN? msg->len : MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN; - memset(safety_allowed_area, 0, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN); - memcpy(safety_allowed_area, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_safety_set_allowed_area.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_safety_set_allowed_area.h deleted file mode 100644 index d50ac5cb..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_safety_set_allowed_area.h +++ /dev/null @@ -1,413 +0,0 @@ -#pragma once -// MESSAGE SAFETY_SET_ALLOWED_AREA PACKING - -#define MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA 54 - - -typedef struct __mavlink_safety_set_allowed_area_t { - float p1x; /*< [m] x position 1 / Latitude 1*/ - float p1y; /*< [m] y position 1 / Longitude 1*/ - float p1z; /*< [m] z position 1 / Altitude 1*/ - float p2x; /*< [m] x position 2 / Latitude 2*/ - float p2y; /*< [m] y position 2 / Longitude 2*/ - float p2z; /*< [m] z position 2 / Altitude 2*/ - uint8_t target_system; /*< System ID*/ - uint8_t target_component; /*< Component ID*/ - uint8_t frame; /*< Coordinate frame. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down.*/ -} mavlink_safety_set_allowed_area_t; - -#define MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN 27 -#define MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_MIN_LEN 27 -#define MAVLINK_MSG_ID_54_LEN 27 -#define MAVLINK_MSG_ID_54_MIN_LEN 27 - -#define MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_CRC 15 -#define MAVLINK_MSG_ID_54_CRC 15 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_SAFETY_SET_ALLOWED_AREA { \ - 54, \ - "SAFETY_SET_ALLOWED_AREA", \ - 9, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_safety_set_allowed_area_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 25, offsetof(mavlink_safety_set_allowed_area_t, target_component) }, \ - { "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 26, offsetof(mavlink_safety_set_allowed_area_t, frame) }, \ - { "p1x", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_safety_set_allowed_area_t, p1x) }, \ - { "p1y", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_safety_set_allowed_area_t, p1y) }, \ - { "p1z", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_safety_set_allowed_area_t, p1z) }, \ - { "p2x", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_safety_set_allowed_area_t, p2x) }, \ - { "p2y", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_safety_set_allowed_area_t, p2y) }, \ - { "p2z", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_safety_set_allowed_area_t, p2z) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_SAFETY_SET_ALLOWED_AREA { \ - "SAFETY_SET_ALLOWED_AREA", \ - 9, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_safety_set_allowed_area_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 25, offsetof(mavlink_safety_set_allowed_area_t, target_component) }, \ - { "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 26, offsetof(mavlink_safety_set_allowed_area_t, frame) }, \ - { "p1x", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_safety_set_allowed_area_t, p1x) }, \ - { "p1y", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_safety_set_allowed_area_t, p1y) }, \ - { "p1z", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_safety_set_allowed_area_t, p1z) }, \ - { "p2x", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_safety_set_allowed_area_t, p2x) }, \ - { "p2y", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_safety_set_allowed_area_t, p2y) }, \ - { "p2z", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_safety_set_allowed_area_t, p2z) }, \ - } \ -} -#endif - -/** - * @brief Pack a safety_set_allowed_area message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID - * @param target_component Component ID - * @param frame Coordinate frame. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. - * @param p1x [m] x position 1 / Latitude 1 - * @param p1y [m] y position 1 / Longitude 1 - * @param p1z [m] z position 1 / Altitude 1 - * @param p2x [m] x position 2 / Latitude 2 - * @param p2y [m] y position 2 / Longitude 2 - * @param p2z [m] z position 2 / Altitude 2 - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_safety_set_allowed_area_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component, uint8_t frame, float p1x, float p1y, float p1z, float p2x, float p2y, float p2z) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN]; - _mav_put_float(buf, 0, p1x); - _mav_put_float(buf, 4, p1y); - _mav_put_float(buf, 8, p1z); - _mav_put_float(buf, 12, p2x); - _mav_put_float(buf, 16, p2y); - _mav_put_float(buf, 20, p2z); - _mav_put_uint8_t(buf, 24, target_system); - _mav_put_uint8_t(buf, 25, target_component); - _mav_put_uint8_t(buf, 26, frame); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN); -#else - mavlink_safety_set_allowed_area_t packet; - packet.p1x = p1x; - packet.p1y = p1y; - packet.p1z = p1z; - packet.p2x = p2x; - packet.p2y = p2y; - packet.p2z = p2z; - packet.target_system = target_system; - packet.target_component = target_component; - packet.frame = frame; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_MIN_LEN, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_CRC); -} - -/** - * @brief Pack a safety_set_allowed_area message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @param frame Coordinate frame. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. - * @param p1x [m] x position 1 / Latitude 1 - * @param p1y [m] y position 1 / Longitude 1 - * @param p1z [m] z position 1 / Altitude 1 - * @param p2x [m] x position 2 / Latitude 2 - * @param p2y [m] y position 2 / Longitude 2 - * @param p2z [m] z position 2 / Altitude 2 - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_safety_set_allowed_area_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component,uint8_t frame,float p1x,float p1y,float p1z,float p2x,float p2y,float p2z) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN]; - _mav_put_float(buf, 0, p1x); - _mav_put_float(buf, 4, p1y); - _mav_put_float(buf, 8, p1z); - _mav_put_float(buf, 12, p2x); - _mav_put_float(buf, 16, p2y); - _mav_put_float(buf, 20, p2z); - _mav_put_uint8_t(buf, 24, target_system); - _mav_put_uint8_t(buf, 25, target_component); - _mav_put_uint8_t(buf, 26, frame); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN); -#else - mavlink_safety_set_allowed_area_t packet; - packet.p1x = p1x; - packet.p1y = p1y; - packet.p1z = p1z; - packet.p2x = p2x; - packet.p2y = p2y; - packet.p2z = p2z; - packet.target_system = target_system; - packet.target_component = target_component; - packet.frame = frame; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_MIN_LEN, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_CRC); -} - -/** - * @brief Encode a safety_set_allowed_area struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param safety_set_allowed_area C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_safety_set_allowed_area_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_safety_set_allowed_area_t* safety_set_allowed_area) -{ - return mavlink_msg_safety_set_allowed_area_pack(system_id, component_id, msg, safety_set_allowed_area->target_system, safety_set_allowed_area->target_component, safety_set_allowed_area->frame, safety_set_allowed_area->p1x, safety_set_allowed_area->p1y, safety_set_allowed_area->p1z, safety_set_allowed_area->p2x, safety_set_allowed_area->p2y, safety_set_allowed_area->p2z); -} - -/** - * @brief Encode a safety_set_allowed_area struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param safety_set_allowed_area C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_safety_set_allowed_area_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_safety_set_allowed_area_t* safety_set_allowed_area) -{ - return mavlink_msg_safety_set_allowed_area_pack_chan(system_id, component_id, chan, msg, safety_set_allowed_area->target_system, safety_set_allowed_area->target_component, safety_set_allowed_area->frame, safety_set_allowed_area->p1x, safety_set_allowed_area->p1y, safety_set_allowed_area->p1z, safety_set_allowed_area->p2x, safety_set_allowed_area->p2y, safety_set_allowed_area->p2z); -} - -/** - * @brief Send a safety_set_allowed_area message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param target_component Component ID - * @param frame Coordinate frame. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. - * @param p1x [m] x position 1 / Latitude 1 - * @param p1y [m] y position 1 / Longitude 1 - * @param p1z [m] z position 1 / Altitude 1 - * @param p2x [m] x position 2 / Latitude 2 - * @param p2y [m] y position 2 / Longitude 2 - * @param p2z [m] z position 2 / Altitude 2 - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_safety_set_allowed_area_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t frame, float p1x, float p1y, float p1z, float p2x, float p2y, float p2z) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN]; - _mav_put_float(buf, 0, p1x); - _mav_put_float(buf, 4, p1y); - _mav_put_float(buf, 8, p1z); - _mav_put_float(buf, 12, p2x); - _mav_put_float(buf, 16, p2y); - _mav_put_float(buf, 20, p2z); - _mav_put_uint8_t(buf, 24, target_system); - _mav_put_uint8_t(buf, 25, target_component); - _mav_put_uint8_t(buf, 26, frame); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA, buf, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_MIN_LEN, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_CRC); -#else - mavlink_safety_set_allowed_area_t packet; - packet.p1x = p1x; - packet.p1y = p1y; - packet.p1z = p1z; - packet.p2x = p2x; - packet.p2y = p2y; - packet.p2z = p2z; - packet.target_system = target_system; - packet.target_component = target_component; - packet.frame = frame; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA, (const char *)&packet, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_MIN_LEN, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_CRC); -#endif -} - -/** - * @brief Send a safety_set_allowed_area message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_safety_set_allowed_area_send_struct(mavlink_channel_t chan, const mavlink_safety_set_allowed_area_t* safety_set_allowed_area) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_safety_set_allowed_area_send(chan, safety_set_allowed_area->target_system, safety_set_allowed_area->target_component, safety_set_allowed_area->frame, safety_set_allowed_area->p1x, safety_set_allowed_area->p1y, safety_set_allowed_area->p1z, safety_set_allowed_area->p2x, safety_set_allowed_area->p2y, safety_set_allowed_area->p2z); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA, (const char *)safety_set_allowed_area, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_MIN_LEN, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_CRC); -#endif -} - -#if MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_safety_set_allowed_area_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t frame, float p1x, float p1y, float p1z, float p2x, float p2y, float p2z) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_float(buf, 0, p1x); - _mav_put_float(buf, 4, p1y); - _mav_put_float(buf, 8, p1z); - _mav_put_float(buf, 12, p2x); - _mav_put_float(buf, 16, p2y); - _mav_put_float(buf, 20, p2z); - _mav_put_uint8_t(buf, 24, target_system); - _mav_put_uint8_t(buf, 25, target_component); - _mav_put_uint8_t(buf, 26, frame); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA, buf, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_MIN_LEN, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_CRC); -#else - mavlink_safety_set_allowed_area_t *packet = (mavlink_safety_set_allowed_area_t *)msgbuf; - packet->p1x = p1x; - packet->p1y = p1y; - packet->p1z = p1z; - packet->p2x = p2x; - packet->p2y = p2y; - packet->p2z = p2z; - packet->target_system = target_system; - packet->target_component = target_component; - packet->frame = frame; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA, (const char *)packet, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_MIN_LEN, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_CRC); -#endif -} -#endif - -#endif - -// MESSAGE SAFETY_SET_ALLOWED_AREA UNPACKING - - -/** - * @brief Get field target_system from safety_set_allowed_area message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_safety_set_allowed_area_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 24); -} - -/** - * @brief Get field target_component from safety_set_allowed_area message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_safety_set_allowed_area_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 25); -} - -/** - * @brief Get field frame from safety_set_allowed_area message - * - * @return Coordinate frame. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. - */ -static inline uint8_t mavlink_msg_safety_set_allowed_area_get_frame(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 26); -} - -/** - * @brief Get field p1x from safety_set_allowed_area message - * - * @return [m] x position 1 / Latitude 1 - */ -static inline float mavlink_msg_safety_set_allowed_area_get_p1x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 0); -} - -/** - * @brief Get field p1y from safety_set_allowed_area message - * - * @return [m] y position 1 / Longitude 1 - */ -static inline float mavlink_msg_safety_set_allowed_area_get_p1y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 4); -} - -/** - * @brief Get field p1z from safety_set_allowed_area message - * - * @return [m] z position 1 / Altitude 1 - */ -static inline float mavlink_msg_safety_set_allowed_area_get_p1z(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field p2x from safety_set_allowed_area message - * - * @return [m] x position 2 / Latitude 2 - */ -static inline float mavlink_msg_safety_set_allowed_area_get_p2x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field p2y from safety_set_allowed_area message - * - * @return [m] y position 2 / Longitude 2 - */ -static inline float mavlink_msg_safety_set_allowed_area_get_p2y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field p2z from safety_set_allowed_area message - * - * @return [m] z position 2 / Altitude 2 - */ -static inline float mavlink_msg_safety_set_allowed_area_get_p2z(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Decode a safety_set_allowed_area message into a struct - * - * @param msg The message to decode - * @param safety_set_allowed_area C-struct to decode the message contents into - */ -static inline void mavlink_msg_safety_set_allowed_area_decode(const mavlink_message_t* msg, mavlink_safety_set_allowed_area_t* safety_set_allowed_area) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - safety_set_allowed_area->p1x = mavlink_msg_safety_set_allowed_area_get_p1x(msg); - safety_set_allowed_area->p1y = mavlink_msg_safety_set_allowed_area_get_p1y(msg); - safety_set_allowed_area->p1z = mavlink_msg_safety_set_allowed_area_get_p1z(msg); - safety_set_allowed_area->p2x = mavlink_msg_safety_set_allowed_area_get_p2x(msg); - safety_set_allowed_area->p2y = mavlink_msg_safety_set_allowed_area_get_p2y(msg); - safety_set_allowed_area->p2z = mavlink_msg_safety_set_allowed_area_get_p2z(msg); - safety_set_allowed_area->target_system = mavlink_msg_safety_set_allowed_area_get_target_system(msg); - safety_set_allowed_area->target_component = mavlink_msg_safety_set_allowed_area_get_target_component(msg); - safety_set_allowed_area->frame = mavlink_msg_safety_set_allowed_area_get_frame(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN? msg->len : MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN; - memset(safety_set_allowed_area, 0, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN); - memcpy(safety_set_allowed_area, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_scaled_imu.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_scaled_imu.h deleted file mode 100644 index fac086f6..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_scaled_imu.h +++ /dev/null @@ -1,463 +0,0 @@ -#pragma once -// MESSAGE SCALED_IMU PACKING - -#define MAVLINK_MSG_ID_SCALED_IMU 26 - - -typedef struct __mavlink_scaled_imu_t { - uint32_t time_boot_ms; /*< [ms] Timestamp (time since system boot).*/ - int16_t xacc; /*< [mG] X acceleration*/ - int16_t yacc; /*< [mG] Y acceleration*/ - int16_t zacc; /*< [mG] Z acceleration*/ - int16_t xgyro; /*< [mrad/s] Angular speed around X axis*/ - int16_t ygyro; /*< [mrad/s] Angular speed around Y axis*/ - int16_t zgyro; /*< [mrad/s] Angular speed around Z axis*/ - int16_t xmag; /*< [mgauss] X Magnetic field*/ - int16_t ymag; /*< [mgauss] Y Magnetic field*/ - int16_t zmag; /*< [mgauss] Z Magnetic field*/ - int16_t temperature; /*< [cdegC] Temperature, 0: IMU does not provide temperature values. If the IMU is at 0C it must send 1 (0.01C).*/ -} mavlink_scaled_imu_t; - -#define MAVLINK_MSG_ID_SCALED_IMU_LEN 24 -#define MAVLINK_MSG_ID_SCALED_IMU_MIN_LEN 22 -#define MAVLINK_MSG_ID_26_LEN 24 -#define MAVLINK_MSG_ID_26_MIN_LEN 22 - -#define MAVLINK_MSG_ID_SCALED_IMU_CRC 170 -#define MAVLINK_MSG_ID_26_CRC 170 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_SCALED_IMU { \ - 26, \ - "SCALED_IMU", \ - 11, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_scaled_imu_t, time_boot_ms) }, \ - { "xacc", NULL, MAVLINK_TYPE_INT16_T, 0, 4, offsetof(mavlink_scaled_imu_t, xacc) }, \ - { "yacc", NULL, MAVLINK_TYPE_INT16_T, 0, 6, offsetof(mavlink_scaled_imu_t, yacc) }, \ - { "zacc", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_scaled_imu_t, zacc) }, \ - { "xgyro", NULL, MAVLINK_TYPE_INT16_T, 0, 10, offsetof(mavlink_scaled_imu_t, xgyro) }, \ - { "ygyro", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_scaled_imu_t, ygyro) }, \ - { "zgyro", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_scaled_imu_t, zgyro) }, \ - { "xmag", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_scaled_imu_t, xmag) }, \ - { "ymag", NULL, MAVLINK_TYPE_INT16_T, 0, 18, offsetof(mavlink_scaled_imu_t, ymag) }, \ - { "zmag", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_scaled_imu_t, zmag) }, \ - { "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 22, offsetof(mavlink_scaled_imu_t, temperature) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_SCALED_IMU { \ - "SCALED_IMU", \ - 11, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_scaled_imu_t, time_boot_ms) }, \ - { "xacc", NULL, MAVLINK_TYPE_INT16_T, 0, 4, offsetof(mavlink_scaled_imu_t, xacc) }, \ - { "yacc", NULL, MAVLINK_TYPE_INT16_T, 0, 6, offsetof(mavlink_scaled_imu_t, yacc) }, \ - { "zacc", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_scaled_imu_t, zacc) }, \ - { "xgyro", NULL, MAVLINK_TYPE_INT16_T, 0, 10, offsetof(mavlink_scaled_imu_t, xgyro) }, \ - { "ygyro", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_scaled_imu_t, ygyro) }, \ - { "zgyro", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_scaled_imu_t, zgyro) }, \ - { "xmag", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_scaled_imu_t, xmag) }, \ - { "ymag", NULL, MAVLINK_TYPE_INT16_T, 0, 18, offsetof(mavlink_scaled_imu_t, ymag) }, \ - { "zmag", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_scaled_imu_t, zmag) }, \ - { "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 22, offsetof(mavlink_scaled_imu_t, temperature) }, \ - } \ -} -#endif - -/** - * @brief Pack a scaled_imu message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param time_boot_ms [ms] Timestamp (time since system boot). - * @param xacc [mG] X acceleration - * @param yacc [mG] Y acceleration - * @param zacc [mG] Z acceleration - * @param xgyro [mrad/s] Angular speed around X axis - * @param ygyro [mrad/s] Angular speed around Y axis - * @param zgyro [mrad/s] Angular speed around Z axis - * @param xmag [mgauss] X Magnetic field - * @param ymag [mgauss] Y Magnetic field - * @param zmag [mgauss] Z Magnetic field - * @param temperature [cdegC] Temperature, 0: IMU does not provide temperature values. If the IMU is at 0C it must send 1 (0.01C). - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_scaled_imu_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint32_t time_boot_ms, int16_t xacc, int16_t yacc, int16_t zacc, int16_t xgyro, int16_t ygyro, int16_t zgyro, int16_t xmag, int16_t ymag, int16_t zmag, int16_t temperature) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SCALED_IMU_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_int16_t(buf, 4, xacc); - _mav_put_int16_t(buf, 6, yacc); - _mav_put_int16_t(buf, 8, zacc); - _mav_put_int16_t(buf, 10, xgyro); - _mav_put_int16_t(buf, 12, ygyro); - _mav_put_int16_t(buf, 14, zgyro); - _mav_put_int16_t(buf, 16, xmag); - _mav_put_int16_t(buf, 18, ymag); - _mav_put_int16_t(buf, 20, zmag); - _mav_put_int16_t(buf, 22, temperature); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SCALED_IMU_LEN); -#else - mavlink_scaled_imu_t packet; - packet.time_boot_ms = time_boot_ms; - packet.xacc = xacc; - packet.yacc = yacc; - packet.zacc = zacc; - packet.xgyro = xgyro; - packet.ygyro = ygyro; - packet.zgyro = zgyro; - packet.xmag = xmag; - packet.ymag = ymag; - packet.zmag = zmag; - packet.temperature = temperature; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SCALED_IMU_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SCALED_IMU; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SCALED_IMU_MIN_LEN, MAVLINK_MSG_ID_SCALED_IMU_LEN, MAVLINK_MSG_ID_SCALED_IMU_CRC); -} - -/** - * @brief Pack a scaled_imu message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_boot_ms [ms] Timestamp (time since system boot). - * @param xacc [mG] X acceleration - * @param yacc [mG] Y acceleration - * @param zacc [mG] Z acceleration - * @param xgyro [mrad/s] Angular speed around X axis - * @param ygyro [mrad/s] Angular speed around Y axis - * @param zgyro [mrad/s] Angular speed around Z axis - * @param xmag [mgauss] X Magnetic field - * @param ymag [mgauss] Y Magnetic field - * @param zmag [mgauss] Z Magnetic field - * @param temperature [cdegC] Temperature, 0: IMU does not provide temperature values. If the IMU is at 0C it must send 1 (0.01C). - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_scaled_imu_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint32_t time_boot_ms,int16_t xacc,int16_t yacc,int16_t zacc,int16_t xgyro,int16_t ygyro,int16_t zgyro,int16_t xmag,int16_t ymag,int16_t zmag,int16_t temperature) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SCALED_IMU_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_int16_t(buf, 4, xacc); - _mav_put_int16_t(buf, 6, yacc); - _mav_put_int16_t(buf, 8, zacc); - _mav_put_int16_t(buf, 10, xgyro); - _mav_put_int16_t(buf, 12, ygyro); - _mav_put_int16_t(buf, 14, zgyro); - _mav_put_int16_t(buf, 16, xmag); - _mav_put_int16_t(buf, 18, ymag); - _mav_put_int16_t(buf, 20, zmag); - _mav_put_int16_t(buf, 22, temperature); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SCALED_IMU_LEN); -#else - mavlink_scaled_imu_t packet; - packet.time_boot_ms = time_boot_ms; - packet.xacc = xacc; - packet.yacc = yacc; - packet.zacc = zacc; - packet.xgyro = xgyro; - packet.ygyro = ygyro; - packet.zgyro = zgyro; - packet.xmag = xmag; - packet.ymag = ymag; - packet.zmag = zmag; - packet.temperature = temperature; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SCALED_IMU_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SCALED_IMU; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SCALED_IMU_MIN_LEN, MAVLINK_MSG_ID_SCALED_IMU_LEN, MAVLINK_MSG_ID_SCALED_IMU_CRC); -} - -/** - * @brief Encode a scaled_imu struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param scaled_imu C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_scaled_imu_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_scaled_imu_t* scaled_imu) -{ - return mavlink_msg_scaled_imu_pack(system_id, component_id, msg, scaled_imu->time_boot_ms, scaled_imu->xacc, scaled_imu->yacc, scaled_imu->zacc, scaled_imu->xgyro, scaled_imu->ygyro, scaled_imu->zgyro, scaled_imu->xmag, scaled_imu->ymag, scaled_imu->zmag, scaled_imu->temperature); -} - -/** - * @brief Encode a scaled_imu struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param scaled_imu C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_scaled_imu_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_scaled_imu_t* scaled_imu) -{ - return mavlink_msg_scaled_imu_pack_chan(system_id, component_id, chan, msg, scaled_imu->time_boot_ms, scaled_imu->xacc, scaled_imu->yacc, scaled_imu->zacc, scaled_imu->xgyro, scaled_imu->ygyro, scaled_imu->zgyro, scaled_imu->xmag, scaled_imu->ymag, scaled_imu->zmag, scaled_imu->temperature); -} - -/** - * @brief Send a scaled_imu message - * @param chan MAVLink channel to send the message - * - * @param time_boot_ms [ms] Timestamp (time since system boot). - * @param xacc [mG] X acceleration - * @param yacc [mG] Y acceleration - * @param zacc [mG] Z acceleration - * @param xgyro [mrad/s] Angular speed around X axis - * @param ygyro [mrad/s] Angular speed around Y axis - * @param zgyro [mrad/s] Angular speed around Z axis - * @param xmag [mgauss] X Magnetic field - * @param ymag [mgauss] Y Magnetic field - * @param zmag [mgauss] Z Magnetic field - * @param temperature [cdegC] Temperature, 0: IMU does not provide temperature values. If the IMU is at 0C it must send 1 (0.01C). - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_scaled_imu_send(mavlink_channel_t chan, uint32_t time_boot_ms, int16_t xacc, int16_t yacc, int16_t zacc, int16_t xgyro, int16_t ygyro, int16_t zgyro, int16_t xmag, int16_t ymag, int16_t zmag, int16_t temperature) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SCALED_IMU_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_int16_t(buf, 4, xacc); - _mav_put_int16_t(buf, 6, yacc); - _mav_put_int16_t(buf, 8, zacc); - _mav_put_int16_t(buf, 10, xgyro); - _mav_put_int16_t(buf, 12, ygyro); - _mav_put_int16_t(buf, 14, zgyro); - _mav_put_int16_t(buf, 16, xmag); - _mav_put_int16_t(buf, 18, ymag); - _mav_put_int16_t(buf, 20, zmag); - _mav_put_int16_t(buf, 22, temperature); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU, buf, MAVLINK_MSG_ID_SCALED_IMU_MIN_LEN, MAVLINK_MSG_ID_SCALED_IMU_LEN, MAVLINK_MSG_ID_SCALED_IMU_CRC); -#else - mavlink_scaled_imu_t packet; - packet.time_boot_ms = time_boot_ms; - packet.xacc = xacc; - packet.yacc = yacc; - packet.zacc = zacc; - packet.xgyro = xgyro; - packet.ygyro = ygyro; - packet.zgyro = zgyro; - packet.xmag = xmag; - packet.ymag = ymag; - packet.zmag = zmag; - packet.temperature = temperature; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU, (const char *)&packet, MAVLINK_MSG_ID_SCALED_IMU_MIN_LEN, MAVLINK_MSG_ID_SCALED_IMU_LEN, MAVLINK_MSG_ID_SCALED_IMU_CRC); -#endif -} - -/** - * @brief Send a scaled_imu message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_scaled_imu_send_struct(mavlink_channel_t chan, const mavlink_scaled_imu_t* scaled_imu) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_scaled_imu_send(chan, scaled_imu->time_boot_ms, scaled_imu->xacc, scaled_imu->yacc, scaled_imu->zacc, scaled_imu->xgyro, scaled_imu->ygyro, scaled_imu->zgyro, scaled_imu->xmag, scaled_imu->ymag, scaled_imu->zmag, scaled_imu->temperature); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU, (const char *)scaled_imu, MAVLINK_MSG_ID_SCALED_IMU_MIN_LEN, MAVLINK_MSG_ID_SCALED_IMU_LEN, MAVLINK_MSG_ID_SCALED_IMU_CRC); -#endif -} - -#if MAVLINK_MSG_ID_SCALED_IMU_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_scaled_imu_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, int16_t xacc, int16_t yacc, int16_t zacc, int16_t xgyro, int16_t ygyro, int16_t zgyro, int16_t xmag, int16_t ymag, int16_t zmag, int16_t temperature) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_int16_t(buf, 4, xacc); - _mav_put_int16_t(buf, 6, yacc); - _mav_put_int16_t(buf, 8, zacc); - _mav_put_int16_t(buf, 10, xgyro); - _mav_put_int16_t(buf, 12, ygyro); - _mav_put_int16_t(buf, 14, zgyro); - _mav_put_int16_t(buf, 16, xmag); - _mav_put_int16_t(buf, 18, ymag); - _mav_put_int16_t(buf, 20, zmag); - _mav_put_int16_t(buf, 22, temperature); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU, buf, MAVLINK_MSG_ID_SCALED_IMU_MIN_LEN, MAVLINK_MSG_ID_SCALED_IMU_LEN, MAVLINK_MSG_ID_SCALED_IMU_CRC); -#else - mavlink_scaled_imu_t *packet = (mavlink_scaled_imu_t *)msgbuf; - packet->time_boot_ms = time_boot_ms; - packet->xacc = xacc; - packet->yacc = yacc; - packet->zacc = zacc; - packet->xgyro = xgyro; - packet->ygyro = ygyro; - packet->zgyro = zgyro; - packet->xmag = xmag; - packet->ymag = ymag; - packet->zmag = zmag; - packet->temperature = temperature; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU, (const char *)packet, MAVLINK_MSG_ID_SCALED_IMU_MIN_LEN, MAVLINK_MSG_ID_SCALED_IMU_LEN, MAVLINK_MSG_ID_SCALED_IMU_CRC); -#endif -} -#endif - -#endif - -// MESSAGE SCALED_IMU UNPACKING - - -/** - * @brief Get field time_boot_ms from scaled_imu message - * - * @return [ms] Timestamp (time since system boot). - */ -static inline uint32_t mavlink_msg_scaled_imu_get_time_boot_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field xacc from scaled_imu message - * - * @return [mG] X acceleration - */ -static inline int16_t mavlink_msg_scaled_imu_get_xacc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 4); -} - -/** - * @brief Get field yacc from scaled_imu message - * - * @return [mG] Y acceleration - */ -static inline int16_t mavlink_msg_scaled_imu_get_yacc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 6); -} - -/** - * @brief Get field zacc from scaled_imu message - * - * @return [mG] Z acceleration - */ -static inline int16_t mavlink_msg_scaled_imu_get_zacc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 8); -} - -/** - * @brief Get field xgyro from scaled_imu message - * - * @return [mrad/s] Angular speed around X axis - */ -static inline int16_t mavlink_msg_scaled_imu_get_xgyro(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 10); -} - -/** - * @brief Get field ygyro from scaled_imu message - * - * @return [mrad/s] Angular speed around Y axis - */ -static inline int16_t mavlink_msg_scaled_imu_get_ygyro(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 12); -} - -/** - * @brief Get field zgyro from scaled_imu message - * - * @return [mrad/s] Angular speed around Z axis - */ -static inline int16_t mavlink_msg_scaled_imu_get_zgyro(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 14); -} - -/** - * @brief Get field xmag from scaled_imu message - * - * @return [mgauss] X Magnetic field - */ -static inline int16_t mavlink_msg_scaled_imu_get_xmag(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 16); -} - -/** - * @brief Get field ymag from scaled_imu message - * - * @return [mgauss] Y Magnetic field - */ -static inline int16_t mavlink_msg_scaled_imu_get_ymag(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 18); -} - -/** - * @brief Get field zmag from scaled_imu message - * - * @return [mgauss] Z Magnetic field - */ -static inline int16_t mavlink_msg_scaled_imu_get_zmag(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 20); -} - -/** - * @brief Get field temperature from scaled_imu message - * - * @return [cdegC] Temperature, 0: IMU does not provide temperature values. If the IMU is at 0C it must send 1 (0.01C). - */ -static inline int16_t mavlink_msg_scaled_imu_get_temperature(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 22); -} - -/** - * @brief Decode a scaled_imu message into a struct - * - * @param msg The message to decode - * @param scaled_imu C-struct to decode the message contents into - */ -static inline void mavlink_msg_scaled_imu_decode(const mavlink_message_t* msg, mavlink_scaled_imu_t* scaled_imu) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - scaled_imu->time_boot_ms = mavlink_msg_scaled_imu_get_time_boot_ms(msg); - scaled_imu->xacc = mavlink_msg_scaled_imu_get_xacc(msg); - scaled_imu->yacc = mavlink_msg_scaled_imu_get_yacc(msg); - scaled_imu->zacc = mavlink_msg_scaled_imu_get_zacc(msg); - scaled_imu->xgyro = mavlink_msg_scaled_imu_get_xgyro(msg); - scaled_imu->ygyro = mavlink_msg_scaled_imu_get_ygyro(msg); - scaled_imu->zgyro = mavlink_msg_scaled_imu_get_zgyro(msg); - scaled_imu->xmag = mavlink_msg_scaled_imu_get_xmag(msg); - scaled_imu->ymag = mavlink_msg_scaled_imu_get_ymag(msg); - scaled_imu->zmag = mavlink_msg_scaled_imu_get_zmag(msg); - scaled_imu->temperature = mavlink_msg_scaled_imu_get_temperature(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_SCALED_IMU_LEN? msg->len : MAVLINK_MSG_ID_SCALED_IMU_LEN; - memset(scaled_imu, 0, MAVLINK_MSG_ID_SCALED_IMU_LEN); - memcpy(scaled_imu, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_scaled_imu2.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_scaled_imu2.h deleted file mode 100644 index 508fdff7..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_scaled_imu2.h +++ /dev/null @@ -1,463 +0,0 @@ -#pragma once -// MESSAGE SCALED_IMU2 PACKING - -#define MAVLINK_MSG_ID_SCALED_IMU2 116 - - -typedef struct __mavlink_scaled_imu2_t { - uint32_t time_boot_ms; /*< [ms] Timestamp (time since system boot).*/ - int16_t xacc; /*< [mG] X acceleration*/ - int16_t yacc; /*< [mG] Y acceleration*/ - int16_t zacc; /*< [mG] Z acceleration*/ - int16_t xgyro; /*< [mrad/s] Angular speed around X axis*/ - int16_t ygyro; /*< [mrad/s] Angular speed around Y axis*/ - int16_t zgyro; /*< [mrad/s] Angular speed around Z axis*/ - int16_t xmag; /*< [mgauss] X Magnetic field*/ - int16_t ymag; /*< [mgauss] Y Magnetic field*/ - int16_t zmag; /*< [mgauss] Z Magnetic field*/ - int16_t temperature; /*< [cdegC] Temperature, 0: IMU does not provide temperature values. If the IMU is at 0C it must send 1 (0.01C).*/ -} mavlink_scaled_imu2_t; - -#define MAVLINK_MSG_ID_SCALED_IMU2_LEN 24 -#define MAVLINK_MSG_ID_SCALED_IMU2_MIN_LEN 22 -#define MAVLINK_MSG_ID_116_LEN 24 -#define MAVLINK_MSG_ID_116_MIN_LEN 22 - -#define MAVLINK_MSG_ID_SCALED_IMU2_CRC 76 -#define MAVLINK_MSG_ID_116_CRC 76 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_SCALED_IMU2 { \ - 116, \ - "SCALED_IMU2", \ - 11, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_scaled_imu2_t, time_boot_ms) }, \ - { "xacc", NULL, MAVLINK_TYPE_INT16_T, 0, 4, offsetof(mavlink_scaled_imu2_t, xacc) }, \ - { "yacc", NULL, MAVLINK_TYPE_INT16_T, 0, 6, offsetof(mavlink_scaled_imu2_t, yacc) }, \ - { "zacc", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_scaled_imu2_t, zacc) }, \ - { "xgyro", NULL, MAVLINK_TYPE_INT16_T, 0, 10, offsetof(mavlink_scaled_imu2_t, xgyro) }, \ - { "ygyro", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_scaled_imu2_t, ygyro) }, \ - { "zgyro", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_scaled_imu2_t, zgyro) }, \ - { "xmag", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_scaled_imu2_t, xmag) }, \ - { "ymag", NULL, MAVLINK_TYPE_INT16_T, 0, 18, offsetof(mavlink_scaled_imu2_t, ymag) }, \ - { "zmag", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_scaled_imu2_t, zmag) }, \ - { "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 22, offsetof(mavlink_scaled_imu2_t, temperature) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_SCALED_IMU2 { \ - "SCALED_IMU2", \ - 11, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_scaled_imu2_t, time_boot_ms) }, \ - { "xacc", NULL, MAVLINK_TYPE_INT16_T, 0, 4, offsetof(mavlink_scaled_imu2_t, xacc) }, \ - { "yacc", NULL, MAVLINK_TYPE_INT16_T, 0, 6, offsetof(mavlink_scaled_imu2_t, yacc) }, \ - { "zacc", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_scaled_imu2_t, zacc) }, \ - { "xgyro", NULL, MAVLINK_TYPE_INT16_T, 0, 10, offsetof(mavlink_scaled_imu2_t, xgyro) }, \ - { "ygyro", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_scaled_imu2_t, ygyro) }, \ - { "zgyro", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_scaled_imu2_t, zgyro) }, \ - { "xmag", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_scaled_imu2_t, xmag) }, \ - { "ymag", NULL, MAVLINK_TYPE_INT16_T, 0, 18, offsetof(mavlink_scaled_imu2_t, ymag) }, \ - { "zmag", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_scaled_imu2_t, zmag) }, \ - { "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 22, offsetof(mavlink_scaled_imu2_t, temperature) }, \ - } \ -} -#endif - -/** - * @brief Pack a scaled_imu2 message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param time_boot_ms [ms] Timestamp (time since system boot). - * @param xacc [mG] X acceleration - * @param yacc [mG] Y acceleration - * @param zacc [mG] Z acceleration - * @param xgyro [mrad/s] Angular speed around X axis - * @param ygyro [mrad/s] Angular speed around Y axis - * @param zgyro [mrad/s] Angular speed around Z axis - * @param xmag [mgauss] X Magnetic field - * @param ymag [mgauss] Y Magnetic field - * @param zmag [mgauss] Z Magnetic field - * @param temperature [cdegC] Temperature, 0: IMU does not provide temperature values. If the IMU is at 0C it must send 1 (0.01C). - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_scaled_imu2_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint32_t time_boot_ms, int16_t xacc, int16_t yacc, int16_t zacc, int16_t xgyro, int16_t ygyro, int16_t zgyro, int16_t xmag, int16_t ymag, int16_t zmag, int16_t temperature) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SCALED_IMU2_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_int16_t(buf, 4, xacc); - _mav_put_int16_t(buf, 6, yacc); - _mav_put_int16_t(buf, 8, zacc); - _mav_put_int16_t(buf, 10, xgyro); - _mav_put_int16_t(buf, 12, ygyro); - _mav_put_int16_t(buf, 14, zgyro); - _mav_put_int16_t(buf, 16, xmag); - _mav_put_int16_t(buf, 18, ymag); - _mav_put_int16_t(buf, 20, zmag); - _mav_put_int16_t(buf, 22, temperature); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SCALED_IMU2_LEN); -#else - mavlink_scaled_imu2_t packet; - packet.time_boot_ms = time_boot_ms; - packet.xacc = xacc; - packet.yacc = yacc; - packet.zacc = zacc; - packet.xgyro = xgyro; - packet.ygyro = ygyro; - packet.zgyro = zgyro; - packet.xmag = xmag; - packet.ymag = ymag; - packet.zmag = zmag; - packet.temperature = temperature; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SCALED_IMU2_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SCALED_IMU2; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SCALED_IMU2_MIN_LEN, MAVLINK_MSG_ID_SCALED_IMU2_LEN, MAVLINK_MSG_ID_SCALED_IMU2_CRC); -} - -/** - * @brief Pack a scaled_imu2 message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_boot_ms [ms] Timestamp (time since system boot). - * @param xacc [mG] X acceleration - * @param yacc [mG] Y acceleration - * @param zacc [mG] Z acceleration - * @param xgyro [mrad/s] Angular speed around X axis - * @param ygyro [mrad/s] Angular speed around Y axis - * @param zgyro [mrad/s] Angular speed around Z axis - * @param xmag [mgauss] X Magnetic field - * @param ymag [mgauss] Y Magnetic field - * @param zmag [mgauss] Z Magnetic field - * @param temperature [cdegC] Temperature, 0: IMU does not provide temperature values. If the IMU is at 0C it must send 1 (0.01C). - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_scaled_imu2_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint32_t time_boot_ms,int16_t xacc,int16_t yacc,int16_t zacc,int16_t xgyro,int16_t ygyro,int16_t zgyro,int16_t xmag,int16_t ymag,int16_t zmag,int16_t temperature) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SCALED_IMU2_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_int16_t(buf, 4, xacc); - _mav_put_int16_t(buf, 6, yacc); - _mav_put_int16_t(buf, 8, zacc); - _mav_put_int16_t(buf, 10, xgyro); - _mav_put_int16_t(buf, 12, ygyro); - _mav_put_int16_t(buf, 14, zgyro); - _mav_put_int16_t(buf, 16, xmag); - _mav_put_int16_t(buf, 18, ymag); - _mav_put_int16_t(buf, 20, zmag); - _mav_put_int16_t(buf, 22, temperature); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SCALED_IMU2_LEN); -#else - mavlink_scaled_imu2_t packet; - packet.time_boot_ms = time_boot_ms; - packet.xacc = xacc; - packet.yacc = yacc; - packet.zacc = zacc; - packet.xgyro = xgyro; - packet.ygyro = ygyro; - packet.zgyro = zgyro; - packet.xmag = xmag; - packet.ymag = ymag; - packet.zmag = zmag; - packet.temperature = temperature; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SCALED_IMU2_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SCALED_IMU2; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SCALED_IMU2_MIN_LEN, MAVLINK_MSG_ID_SCALED_IMU2_LEN, MAVLINK_MSG_ID_SCALED_IMU2_CRC); -} - -/** - * @brief Encode a scaled_imu2 struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param scaled_imu2 C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_scaled_imu2_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_scaled_imu2_t* scaled_imu2) -{ - return mavlink_msg_scaled_imu2_pack(system_id, component_id, msg, scaled_imu2->time_boot_ms, scaled_imu2->xacc, scaled_imu2->yacc, scaled_imu2->zacc, scaled_imu2->xgyro, scaled_imu2->ygyro, scaled_imu2->zgyro, scaled_imu2->xmag, scaled_imu2->ymag, scaled_imu2->zmag, scaled_imu2->temperature); -} - -/** - * @brief Encode a scaled_imu2 struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param scaled_imu2 C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_scaled_imu2_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_scaled_imu2_t* scaled_imu2) -{ - return mavlink_msg_scaled_imu2_pack_chan(system_id, component_id, chan, msg, scaled_imu2->time_boot_ms, scaled_imu2->xacc, scaled_imu2->yacc, scaled_imu2->zacc, scaled_imu2->xgyro, scaled_imu2->ygyro, scaled_imu2->zgyro, scaled_imu2->xmag, scaled_imu2->ymag, scaled_imu2->zmag, scaled_imu2->temperature); -} - -/** - * @brief Send a scaled_imu2 message - * @param chan MAVLink channel to send the message - * - * @param time_boot_ms [ms] Timestamp (time since system boot). - * @param xacc [mG] X acceleration - * @param yacc [mG] Y acceleration - * @param zacc [mG] Z acceleration - * @param xgyro [mrad/s] Angular speed around X axis - * @param ygyro [mrad/s] Angular speed around Y axis - * @param zgyro [mrad/s] Angular speed around Z axis - * @param xmag [mgauss] X Magnetic field - * @param ymag [mgauss] Y Magnetic field - * @param zmag [mgauss] Z Magnetic field - * @param temperature [cdegC] Temperature, 0: IMU does not provide temperature values. If the IMU is at 0C it must send 1 (0.01C). - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_scaled_imu2_send(mavlink_channel_t chan, uint32_t time_boot_ms, int16_t xacc, int16_t yacc, int16_t zacc, int16_t xgyro, int16_t ygyro, int16_t zgyro, int16_t xmag, int16_t ymag, int16_t zmag, int16_t temperature) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SCALED_IMU2_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_int16_t(buf, 4, xacc); - _mav_put_int16_t(buf, 6, yacc); - _mav_put_int16_t(buf, 8, zacc); - _mav_put_int16_t(buf, 10, xgyro); - _mav_put_int16_t(buf, 12, ygyro); - _mav_put_int16_t(buf, 14, zgyro); - _mav_put_int16_t(buf, 16, xmag); - _mav_put_int16_t(buf, 18, ymag); - _mav_put_int16_t(buf, 20, zmag); - _mav_put_int16_t(buf, 22, temperature); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU2, buf, MAVLINK_MSG_ID_SCALED_IMU2_MIN_LEN, MAVLINK_MSG_ID_SCALED_IMU2_LEN, MAVLINK_MSG_ID_SCALED_IMU2_CRC); -#else - mavlink_scaled_imu2_t packet; - packet.time_boot_ms = time_boot_ms; - packet.xacc = xacc; - packet.yacc = yacc; - packet.zacc = zacc; - packet.xgyro = xgyro; - packet.ygyro = ygyro; - packet.zgyro = zgyro; - packet.xmag = xmag; - packet.ymag = ymag; - packet.zmag = zmag; - packet.temperature = temperature; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU2, (const char *)&packet, MAVLINK_MSG_ID_SCALED_IMU2_MIN_LEN, MAVLINK_MSG_ID_SCALED_IMU2_LEN, MAVLINK_MSG_ID_SCALED_IMU2_CRC); -#endif -} - -/** - * @brief Send a scaled_imu2 message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_scaled_imu2_send_struct(mavlink_channel_t chan, const mavlink_scaled_imu2_t* scaled_imu2) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_scaled_imu2_send(chan, scaled_imu2->time_boot_ms, scaled_imu2->xacc, scaled_imu2->yacc, scaled_imu2->zacc, scaled_imu2->xgyro, scaled_imu2->ygyro, scaled_imu2->zgyro, scaled_imu2->xmag, scaled_imu2->ymag, scaled_imu2->zmag, scaled_imu2->temperature); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU2, (const char *)scaled_imu2, MAVLINK_MSG_ID_SCALED_IMU2_MIN_LEN, MAVLINK_MSG_ID_SCALED_IMU2_LEN, MAVLINK_MSG_ID_SCALED_IMU2_CRC); -#endif -} - -#if MAVLINK_MSG_ID_SCALED_IMU2_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_scaled_imu2_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, int16_t xacc, int16_t yacc, int16_t zacc, int16_t xgyro, int16_t ygyro, int16_t zgyro, int16_t xmag, int16_t ymag, int16_t zmag, int16_t temperature) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_int16_t(buf, 4, xacc); - _mav_put_int16_t(buf, 6, yacc); - _mav_put_int16_t(buf, 8, zacc); - _mav_put_int16_t(buf, 10, xgyro); - _mav_put_int16_t(buf, 12, ygyro); - _mav_put_int16_t(buf, 14, zgyro); - _mav_put_int16_t(buf, 16, xmag); - _mav_put_int16_t(buf, 18, ymag); - _mav_put_int16_t(buf, 20, zmag); - _mav_put_int16_t(buf, 22, temperature); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU2, buf, MAVLINK_MSG_ID_SCALED_IMU2_MIN_LEN, MAVLINK_MSG_ID_SCALED_IMU2_LEN, MAVLINK_MSG_ID_SCALED_IMU2_CRC); -#else - mavlink_scaled_imu2_t *packet = (mavlink_scaled_imu2_t *)msgbuf; - packet->time_boot_ms = time_boot_ms; - packet->xacc = xacc; - packet->yacc = yacc; - packet->zacc = zacc; - packet->xgyro = xgyro; - packet->ygyro = ygyro; - packet->zgyro = zgyro; - packet->xmag = xmag; - packet->ymag = ymag; - packet->zmag = zmag; - packet->temperature = temperature; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU2, (const char *)packet, MAVLINK_MSG_ID_SCALED_IMU2_MIN_LEN, MAVLINK_MSG_ID_SCALED_IMU2_LEN, MAVLINK_MSG_ID_SCALED_IMU2_CRC); -#endif -} -#endif - -#endif - -// MESSAGE SCALED_IMU2 UNPACKING - - -/** - * @brief Get field time_boot_ms from scaled_imu2 message - * - * @return [ms] Timestamp (time since system boot). - */ -static inline uint32_t mavlink_msg_scaled_imu2_get_time_boot_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field xacc from scaled_imu2 message - * - * @return [mG] X acceleration - */ -static inline int16_t mavlink_msg_scaled_imu2_get_xacc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 4); -} - -/** - * @brief Get field yacc from scaled_imu2 message - * - * @return [mG] Y acceleration - */ -static inline int16_t mavlink_msg_scaled_imu2_get_yacc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 6); -} - -/** - * @brief Get field zacc from scaled_imu2 message - * - * @return [mG] Z acceleration - */ -static inline int16_t mavlink_msg_scaled_imu2_get_zacc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 8); -} - -/** - * @brief Get field xgyro from scaled_imu2 message - * - * @return [mrad/s] Angular speed around X axis - */ -static inline int16_t mavlink_msg_scaled_imu2_get_xgyro(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 10); -} - -/** - * @brief Get field ygyro from scaled_imu2 message - * - * @return [mrad/s] Angular speed around Y axis - */ -static inline int16_t mavlink_msg_scaled_imu2_get_ygyro(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 12); -} - -/** - * @brief Get field zgyro from scaled_imu2 message - * - * @return [mrad/s] Angular speed around Z axis - */ -static inline int16_t mavlink_msg_scaled_imu2_get_zgyro(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 14); -} - -/** - * @brief Get field xmag from scaled_imu2 message - * - * @return [mgauss] X Magnetic field - */ -static inline int16_t mavlink_msg_scaled_imu2_get_xmag(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 16); -} - -/** - * @brief Get field ymag from scaled_imu2 message - * - * @return [mgauss] Y Magnetic field - */ -static inline int16_t mavlink_msg_scaled_imu2_get_ymag(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 18); -} - -/** - * @brief Get field zmag from scaled_imu2 message - * - * @return [mgauss] Z Magnetic field - */ -static inline int16_t mavlink_msg_scaled_imu2_get_zmag(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 20); -} - -/** - * @brief Get field temperature from scaled_imu2 message - * - * @return [cdegC] Temperature, 0: IMU does not provide temperature values. If the IMU is at 0C it must send 1 (0.01C). - */ -static inline int16_t mavlink_msg_scaled_imu2_get_temperature(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 22); -} - -/** - * @brief Decode a scaled_imu2 message into a struct - * - * @param msg The message to decode - * @param scaled_imu2 C-struct to decode the message contents into - */ -static inline void mavlink_msg_scaled_imu2_decode(const mavlink_message_t* msg, mavlink_scaled_imu2_t* scaled_imu2) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - scaled_imu2->time_boot_ms = mavlink_msg_scaled_imu2_get_time_boot_ms(msg); - scaled_imu2->xacc = mavlink_msg_scaled_imu2_get_xacc(msg); - scaled_imu2->yacc = mavlink_msg_scaled_imu2_get_yacc(msg); - scaled_imu2->zacc = mavlink_msg_scaled_imu2_get_zacc(msg); - scaled_imu2->xgyro = mavlink_msg_scaled_imu2_get_xgyro(msg); - scaled_imu2->ygyro = mavlink_msg_scaled_imu2_get_ygyro(msg); - scaled_imu2->zgyro = mavlink_msg_scaled_imu2_get_zgyro(msg); - scaled_imu2->xmag = mavlink_msg_scaled_imu2_get_xmag(msg); - scaled_imu2->ymag = mavlink_msg_scaled_imu2_get_ymag(msg); - scaled_imu2->zmag = mavlink_msg_scaled_imu2_get_zmag(msg); - scaled_imu2->temperature = mavlink_msg_scaled_imu2_get_temperature(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_SCALED_IMU2_LEN? msg->len : MAVLINK_MSG_ID_SCALED_IMU2_LEN; - memset(scaled_imu2, 0, MAVLINK_MSG_ID_SCALED_IMU2_LEN); - memcpy(scaled_imu2, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_scaled_imu3.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_scaled_imu3.h deleted file mode 100644 index cbacc699..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_scaled_imu3.h +++ /dev/null @@ -1,463 +0,0 @@ -#pragma once -// MESSAGE SCALED_IMU3 PACKING - -#define MAVLINK_MSG_ID_SCALED_IMU3 129 - - -typedef struct __mavlink_scaled_imu3_t { - uint32_t time_boot_ms; /*< [ms] Timestamp (time since system boot).*/ - int16_t xacc; /*< [mG] X acceleration*/ - int16_t yacc; /*< [mG] Y acceleration*/ - int16_t zacc; /*< [mG] Z acceleration*/ - int16_t xgyro; /*< [mrad/s] Angular speed around X axis*/ - int16_t ygyro; /*< [mrad/s] Angular speed around Y axis*/ - int16_t zgyro; /*< [mrad/s] Angular speed around Z axis*/ - int16_t xmag; /*< [mgauss] X Magnetic field*/ - int16_t ymag; /*< [mgauss] Y Magnetic field*/ - int16_t zmag; /*< [mgauss] Z Magnetic field*/ - int16_t temperature; /*< [cdegC] Temperature, 0: IMU does not provide temperature values. If the IMU is at 0C it must send 1 (0.01C).*/ -} mavlink_scaled_imu3_t; - -#define MAVLINK_MSG_ID_SCALED_IMU3_LEN 24 -#define MAVLINK_MSG_ID_SCALED_IMU3_MIN_LEN 22 -#define MAVLINK_MSG_ID_129_LEN 24 -#define MAVLINK_MSG_ID_129_MIN_LEN 22 - -#define MAVLINK_MSG_ID_SCALED_IMU3_CRC 46 -#define MAVLINK_MSG_ID_129_CRC 46 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_SCALED_IMU3 { \ - 129, \ - "SCALED_IMU3", \ - 11, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_scaled_imu3_t, time_boot_ms) }, \ - { "xacc", NULL, MAVLINK_TYPE_INT16_T, 0, 4, offsetof(mavlink_scaled_imu3_t, xacc) }, \ - { "yacc", NULL, MAVLINK_TYPE_INT16_T, 0, 6, offsetof(mavlink_scaled_imu3_t, yacc) }, \ - { "zacc", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_scaled_imu3_t, zacc) }, \ - { "xgyro", NULL, MAVLINK_TYPE_INT16_T, 0, 10, offsetof(mavlink_scaled_imu3_t, xgyro) }, \ - { "ygyro", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_scaled_imu3_t, ygyro) }, \ - { "zgyro", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_scaled_imu3_t, zgyro) }, \ - { "xmag", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_scaled_imu3_t, xmag) }, \ - { "ymag", NULL, MAVLINK_TYPE_INT16_T, 0, 18, offsetof(mavlink_scaled_imu3_t, ymag) }, \ - { "zmag", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_scaled_imu3_t, zmag) }, \ - { "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 22, offsetof(mavlink_scaled_imu3_t, temperature) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_SCALED_IMU3 { \ - "SCALED_IMU3", \ - 11, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_scaled_imu3_t, time_boot_ms) }, \ - { "xacc", NULL, MAVLINK_TYPE_INT16_T, 0, 4, offsetof(mavlink_scaled_imu3_t, xacc) }, \ - { "yacc", NULL, MAVLINK_TYPE_INT16_T, 0, 6, offsetof(mavlink_scaled_imu3_t, yacc) }, \ - { "zacc", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_scaled_imu3_t, zacc) }, \ - { "xgyro", NULL, MAVLINK_TYPE_INT16_T, 0, 10, offsetof(mavlink_scaled_imu3_t, xgyro) }, \ - { "ygyro", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_scaled_imu3_t, ygyro) }, \ - { "zgyro", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_scaled_imu3_t, zgyro) }, \ - { "xmag", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_scaled_imu3_t, xmag) }, \ - { "ymag", NULL, MAVLINK_TYPE_INT16_T, 0, 18, offsetof(mavlink_scaled_imu3_t, ymag) }, \ - { "zmag", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_scaled_imu3_t, zmag) }, \ - { "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 22, offsetof(mavlink_scaled_imu3_t, temperature) }, \ - } \ -} -#endif - -/** - * @brief Pack a scaled_imu3 message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param time_boot_ms [ms] Timestamp (time since system boot). - * @param xacc [mG] X acceleration - * @param yacc [mG] Y acceleration - * @param zacc [mG] Z acceleration - * @param xgyro [mrad/s] Angular speed around X axis - * @param ygyro [mrad/s] Angular speed around Y axis - * @param zgyro [mrad/s] Angular speed around Z axis - * @param xmag [mgauss] X Magnetic field - * @param ymag [mgauss] Y Magnetic field - * @param zmag [mgauss] Z Magnetic field - * @param temperature [cdegC] Temperature, 0: IMU does not provide temperature values. If the IMU is at 0C it must send 1 (0.01C). - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_scaled_imu3_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint32_t time_boot_ms, int16_t xacc, int16_t yacc, int16_t zacc, int16_t xgyro, int16_t ygyro, int16_t zgyro, int16_t xmag, int16_t ymag, int16_t zmag, int16_t temperature) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SCALED_IMU3_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_int16_t(buf, 4, xacc); - _mav_put_int16_t(buf, 6, yacc); - _mav_put_int16_t(buf, 8, zacc); - _mav_put_int16_t(buf, 10, xgyro); - _mav_put_int16_t(buf, 12, ygyro); - _mav_put_int16_t(buf, 14, zgyro); - _mav_put_int16_t(buf, 16, xmag); - _mav_put_int16_t(buf, 18, ymag); - _mav_put_int16_t(buf, 20, zmag); - _mav_put_int16_t(buf, 22, temperature); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SCALED_IMU3_LEN); -#else - mavlink_scaled_imu3_t packet; - packet.time_boot_ms = time_boot_ms; - packet.xacc = xacc; - packet.yacc = yacc; - packet.zacc = zacc; - packet.xgyro = xgyro; - packet.ygyro = ygyro; - packet.zgyro = zgyro; - packet.xmag = xmag; - packet.ymag = ymag; - packet.zmag = zmag; - packet.temperature = temperature; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SCALED_IMU3_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SCALED_IMU3; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SCALED_IMU3_MIN_LEN, MAVLINK_MSG_ID_SCALED_IMU3_LEN, MAVLINK_MSG_ID_SCALED_IMU3_CRC); -} - -/** - * @brief Pack a scaled_imu3 message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_boot_ms [ms] Timestamp (time since system boot). - * @param xacc [mG] X acceleration - * @param yacc [mG] Y acceleration - * @param zacc [mG] Z acceleration - * @param xgyro [mrad/s] Angular speed around X axis - * @param ygyro [mrad/s] Angular speed around Y axis - * @param zgyro [mrad/s] Angular speed around Z axis - * @param xmag [mgauss] X Magnetic field - * @param ymag [mgauss] Y Magnetic field - * @param zmag [mgauss] Z Magnetic field - * @param temperature [cdegC] Temperature, 0: IMU does not provide temperature values. If the IMU is at 0C it must send 1 (0.01C). - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_scaled_imu3_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint32_t time_boot_ms,int16_t xacc,int16_t yacc,int16_t zacc,int16_t xgyro,int16_t ygyro,int16_t zgyro,int16_t xmag,int16_t ymag,int16_t zmag,int16_t temperature) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SCALED_IMU3_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_int16_t(buf, 4, xacc); - _mav_put_int16_t(buf, 6, yacc); - _mav_put_int16_t(buf, 8, zacc); - _mav_put_int16_t(buf, 10, xgyro); - _mav_put_int16_t(buf, 12, ygyro); - _mav_put_int16_t(buf, 14, zgyro); - _mav_put_int16_t(buf, 16, xmag); - _mav_put_int16_t(buf, 18, ymag); - _mav_put_int16_t(buf, 20, zmag); - _mav_put_int16_t(buf, 22, temperature); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SCALED_IMU3_LEN); -#else - mavlink_scaled_imu3_t packet; - packet.time_boot_ms = time_boot_ms; - packet.xacc = xacc; - packet.yacc = yacc; - packet.zacc = zacc; - packet.xgyro = xgyro; - packet.ygyro = ygyro; - packet.zgyro = zgyro; - packet.xmag = xmag; - packet.ymag = ymag; - packet.zmag = zmag; - packet.temperature = temperature; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SCALED_IMU3_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SCALED_IMU3; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SCALED_IMU3_MIN_LEN, MAVLINK_MSG_ID_SCALED_IMU3_LEN, MAVLINK_MSG_ID_SCALED_IMU3_CRC); -} - -/** - * @brief Encode a scaled_imu3 struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param scaled_imu3 C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_scaled_imu3_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_scaled_imu3_t* scaled_imu3) -{ - return mavlink_msg_scaled_imu3_pack(system_id, component_id, msg, scaled_imu3->time_boot_ms, scaled_imu3->xacc, scaled_imu3->yacc, scaled_imu3->zacc, scaled_imu3->xgyro, scaled_imu3->ygyro, scaled_imu3->zgyro, scaled_imu3->xmag, scaled_imu3->ymag, scaled_imu3->zmag, scaled_imu3->temperature); -} - -/** - * @brief Encode a scaled_imu3 struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param scaled_imu3 C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_scaled_imu3_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_scaled_imu3_t* scaled_imu3) -{ - return mavlink_msg_scaled_imu3_pack_chan(system_id, component_id, chan, msg, scaled_imu3->time_boot_ms, scaled_imu3->xacc, scaled_imu3->yacc, scaled_imu3->zacc, scaled_imu3->xgyro, scaled_imu3->ygyro, scaled_imu3->zgyro, scaled_imu3->xmag, scaled_imu3->ymag, scaled_imu3->zmag, scaled_imu3->temperature); -} - -/** - * @brief Send a scaled_imu3 message - * @param chan MAVLink channel to send the message - * - * @param time_boot_ms [ms] Timestamp (time since system boot). - * @param xacc [mG] X acceleration - * @param yacc [mG] Y acceleration - * @param zacc [mG] Z acceleration - * @param xgyro [mrad/s] Angular speed around X axis - * @param ygyro [mrad/s] Angular speed around Y axis - * @param zgyro [mrad/s] Angular speed around Z axis - * @param xmag [mgauss] X Magnetic field - * @param ymag [mgauss] Y Magnetic field - * @param zmag [mgauss] Z Magnetic field - * @param temperature [cdegC] Temperature, 0: IMU does not provide temperature values. If the IMU is at 0C it must send 1 (0.01C). - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_scaled_imu3_send(mavlink_channel_t chan, uint32_t time_boot_ms, int16_t xacc, int16_t yacc, int16_t zacc, int16_t xgyro, int16_t ygyro, int16_t zgyro, int16_t xmag, int16_t ymag, int16_t zmag, int16_t temperature) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SCALED_IMU3_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_int16_t(buf, 4, xacc); - _mav_put_int16_t(buf, 6, yacc); - _mav_put_int16_t(buf, 8, zacc); - _mav_put_int16_t(buf, 10, xgyro); - _mav_put_int16_t(buf, 12, ygyro); - _mav_put_int16_t(buf, 14, zgyro); - _mav_put_int16_t(buf, 16, xmag); - _mav_put_int16_t(buf, 18, ymag); - _mav_put_int16_t(buf, 20, zmag); - _mav_put_int16_t(buf, 22, temperature); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU3, buf, MAVLINK_MSG_ID_SCALED_IMU3_MIN_LEN, MAVLINK_MSG_ID_SCALED_IMU3_LEN, MAVLINK_MSG_ID_SCALED_IMU3_CRC); -#else - mavlink_scaled_imu3_t packet; - packet.time_boot_ms = time_boot_ms; - packet.xacc = xacc; - packet.yacc = yacc; - packet.zacc = zacc; - packet.xgyro = xgyro; - packet.ygyro = ygyro; - packet.zgyro = zgyro; - packet.xmag = xmag; - packet.ymag = ymag; - packet.zmag = zmag; - packet.temperature = temperature; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU3, (const char *)&packet, MAVLINK_MSG_ID_SCALED_IMU3_MIN_LEN, MAVLINK_MSG_ID_SCALED_IMU3_LEN, MAVLINK_MSG_ID_SCALED_IMU3_CRC); -#endif -} - -/** - * @brief Send a scaled_imu3 message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_scaled_imu3_send_struct(mavlink_channel_t chan, const mavlink_scaled_imu3_t* scaled_imu3) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_scaled_imu3_send(chan, scaled_imu3->time_boot_ms, scaled_imu3->xacc, scaled_imu3->yacc, scaled_imu3->zacc, scaled_imu3->xgyro, scaled_imu3->ygyro, scaled_imu3->zgyro, scaled_imu3->xmag, scaled_imu3->ymag, scaled_imu3->zmag, scaled_imu3->temperature); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU3, (const char *)scaled_imu3, MAVLINK_MSG_ID_SCALED_IMU3_MIN_LEN, MAVLINK_MSG_ID_SCALED_IMU3_LEN, MAVLINK_MSG_ID_SCALED_IMU3_CRC); -#endif -} - -#if MAVLINK_MSG_ID_SCALED_IMU3_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_scaled_imu3_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, int16_t xacc, int16_t yacc, int16_t zacc, int16_t xgyro, int16_t ygyro, int16_t zgyro, int16_t xmag, int16_t ymag, int16_t zmag, int16_t temperature) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_int16_t(buf, 4, xacc); - _mav_put_int16_t(buf, 6, yacc); - _mav_put_int16_t(buf, 8, zacc); - _mav_put_int16_t(buf, 10, xgyro); - _mav_put_int16_t(buf, 12, ygyro); - _mav_put_int16_t(buf, 14, zgyro); - _mav_put_int16_t(buf, 16, xmag); - _mav_put_int16_t(buf, 18, ymag); - _mav_put_int16_t(buf, 20, zmag); - _mav_put_int16_t(buf, 22, temperature); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU3, buf, MAVLINK_MSG_ID_SCALED_IMU3_MIN_LEN, MAVLINK_MSG_ID_SCALED_IMU3_LEN, MAVLINK_MSG_ID_SCALED_IMU3_CRC); -#else - mavlink_scaled_imu3_t *packet = (mavlink_scaled_imu3_t *)msgbuf; - packet->time_boot_ms = time_boot_ms; - packet->xacc = xacc; - packet->yacc = yacc; - packet->zacc = zacc; - packet->xgyro = xgyro; - packet->ygyro = ygyro; - packet->zgyro = zgyro; - packet->xmag = xmag; - packet->ymag = ymag; - packet->zmag = zmag; - packet->temperature = temperature; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU3, (const char *)packet, MAVLINK_MSG_ID_SCALED_IMU3_MIN_LEN, MAVLINK_MSG_ID_SCALED_IMU3_LEN, MAVLINK_MSG_ID_SCALED_IMU3_CRC); -#endif -} -#endif - -#endif - -// MESSAGE SCALED_IMU3 UNPACKING - - -/** - * @brief Get field time_boot_ms from scaled_imu3 message - * - * @return [ms] Timestamp (time since system boot). - */ -static inline uint32_t mavlink_msg_scaled_imu3_get_time_boot_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field xacc from scaled_imu3 message - * - * @return [mG] X acceleration - */ -static inline int16_t mavlink_msg_scaled_imu3_get_xacc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 4); -} - -/** - * @brief Get field yacc from scaled_imu3 message - * - * @return [mG] Y acceleration - */ -static inline int16_t mavlink_msg_scaled_imu3_get_yacc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 6); -} - -/** - * @brief Get field zacc from scaled_imu3 message - * - * @return [mG] Z acceleration - */ -static inline int16_t mavlink_msg_scaled_imu3_get_zacc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 8); -} - -/** - * @brief Get field xgyro from scaled_imu3 message - * - * @return [mrad/s] Angular speed around X axis - */ -static inline int16_t mavlink_msg_scaled_imu3_get_xgyro(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 10); -} - -/** - * @brief Get field ygyro from scaled_imu3 message - * - * @return [mrad/s] Angular speed around Y axis - */ -static inline int16_t mavlink_msg_scaled_imu3_get_ygyro(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 12); -} - -/** - * @brief Get field zgyro from scaled_imu3 message - * - * @return [mrad/s] Angular speed around Z axis - */ -static inline int16_t mavlink_msg_scaled_imu3_get_zgyro(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 14); -} - -/** - * @brief Get field xmag from scaled_imu3 message - * - * @return [mgauss] X Magnetic field - */ -static inline int16_t mavlink_msg_scaled_imu3_get_xmag(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 16); -} - -/** - * @brief Get field ymag from scaled_imu3 message - * - * @return [mgauss] Y Magnetic field - */ -static inline int16_t mavlink_msg_scaled_imu3_get_ymag(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 18); -} - -/** - * @brief Get field zmag from scaled_imu3 message - * - * @return [mgauss] Z Magnetic field - */ -static inline int16_t mavlink_msg_scaled_imu3_get_zmag(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 20); -} - -/** - * @brief Get field temperature from scaled_imu3 message - * - * @return [cdegC] Temperature, 0: IMU does not provide temperature values. If the IMU is at 0C it must send 1 (0.01C). - */ -static inline int16_t mavlink_msg_scaled_imu3_get_temperature(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 22); -} - -/** - * @brief Decode a scaled_imu3 message into a struct - * - * @param msg The message to decode - * @param scaled_imu3 C-struct to decode the message contents into - */ -static inline void mavlink_msg_scaled_imu3_decode(const mavlink_message_t* msg, mavlink_scaled_imu3_t* scaled_imu3) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - scaled_imu3->time_boot_ms = mavlink_msg_scaled_imu3_get_time_boot_ms(msg); - scaled_imu3->xacc = mavlink_msg_scaled_imu3_get_xacc(msg); - scaled_imu3->yacc = mavlink_msg_scaled_imu3_get_yacc(msg); - scaled_imu3->zacc = mavlink_msg_scaled_imu3_get_zacc(msg); - scaled_imu3->xgyro = mavlink_msg_scaled_imu3_get_xgyro(msg); - scaled_imu3->ygyro = mavlink_msg_scaled_imu3_get_ygyro(msg); - scaled_imu3->zgyro = mavlink_msg_scaled_imu3_get_zgyro(msg); - scaled_imu3->xmag = mavlink_msg_scaled_imu3_get_xmag(msg); - scaled_imu3->ymag = mavlink_msg_scaled_imu3_get_ymag(msg); - scaled_imu3->zmag = mavlink_msg_scaled_imu3_get_zmag(msg); - scaled_imu3->temperature = mavlink_msg_scaled_imu3_get_temperature(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_SCALED_IMU3_LEN? msg->len : MAVLINK_MSG_ID_SCALED_IMU3_LEN; - memset(scaled_imu3, 0, MAVLINK_MSG_ID_SCALED_IMU3_LEN); - memcpy(scaled_imu3, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_scaled_pressure.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_scaled_pressure.h deleted file mode 100644 index fedaeed9..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_scaled_pressure.h +++ /dev/null @@ -1,313 +0,0 @@ -#pragma once -// MESSAGE SCALED_PRESSURE PACKING - -#define MAVLINK_MSG_ID_SCALED_PRESSURE 29 - - -typedef struct __mavlink_scaled_pressure_t { - uint32_t time_boot_ms; /*< [ms] Timestamp (time since system boot).*/ - float press_abs; /*< [hPa] Absolute pressure*/ - float press_diff; /*< [hPa] Differential pressure 1*/ - int16_t temperature; /*< [cdegC] Absolute pressure temperature*/ - int16_t temperature_press_diff; /*< [cdegC] Differential pressure temperature (0, if not available). Report values of 0 (or 1) as 1 cdegC.*/ -} mavlink_scaled_pressure_t; - -#define MAVLINK_MSG_ID_SCALED_PRESSURE_LEN 16 -#define MAVLINK_MSG_ID_SCALED_PRESSURE_MIN_LEN 14 -#define MAVLINK_MSG_ID_29_LEN 16 -#define MAVLINK_MSG_ID_29_MIN_LEN 14 - -#define MAVLINK_MSG_ID_SCALED_PRESSURE_CRC 115 -#define MAVLINK_MSG_ID_29_CRC 115 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_SCALED_PRESSURE { \ - 29, \ - "SCALED_PRESSURE", \ - 5, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_scaled_pressure_t, time_boot_ms) }, \ - { "press_abs", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_scaled_pressure_t, press_abs) }, \ - { "press_diff", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_scaled_pressure_t, press_diff) }, \ - { "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_scaled_pressure_t, temperature) }, \ - { "temperature_press_diff", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_scaled_pressure_t, temperature_press_diff) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_SCALED_PRESSURE { \ - "SCALED_PRESSURE", \ - 5, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_scaled_pressure_t, time_boot_ms) }, \ - { "press_abs", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_scaled_pressure_t, press_abs) }, \ - { "press_diff", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_scaled_pressure_t, press_diff) }, \ - { "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_scaled_pressure_t, temperature) }, \ - { "temperature_press_diff", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_scaled_pressure_t, temperature_press_diff) }, \ - } \ -} -#endif - -/** - * @brief Pack a scaled_pressure message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param time_boot_ms [ms] Timestamp (time since system boot). - * @param press_abs [hPa] Absolute pressure - * @param press_diff [hPa] Differential pressure 1 - * @param temperature [cdegC] Absolute pressure temperature - * @param temperature_press_diff [cdegC] Differential pressure temperature (0, if not available). Report values of 0 (or 1) as 1 cdegC. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_scaled_pressure_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint32_t time_boot_ms, float press_abs, float press_diff, int16_t temperature, int16_t temperature_press_diff) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SCALED_PRESSURE_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, press_abs); - _mav_put_float(buf, 8, press_diff); - _mav_put_int16_t(buf, 12, temperature); - _mav_put_int16_t(buf, 14, temperature_press_diff); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN); -#else - mavlink_scaled_pressure_t packet; - packet.time_boot_ms = time_boot_ms; - packet.press_abs = press_abs; - packet.press_diff = press_diff; - packet.temperature = temperature; - packet.temperature_press_diff = temperature_press_diff; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SCALED_PRESSURE; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SCALED_PRESSURE_MIN_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE_CRC); -} - -/** - * @brief Pack a scaled_pressure message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_boot_ms [ms] Timestamp (time since system boot). - * @param press_abs [hPa] Absolute pressure - * @param press_diff [hPa] Differential pressure 1 - * @param temperature [cdegC] Absolute pressure temperature - * @param temperature_press_diff [cdegC] Differential pressure temperature (0, if not available). Report values of 0 (or 1) as 1 cdegC. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_scaled_pressure_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint32_t time_boot_ms,float press_abs,float press_diff,int16_t temperature,int16_t temperature_press_diff) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SCALED_PRESSURE_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, press_abs); - _mav_put_float(buf, 8, press_diff); - _mav_put_int16_t(buf, 12, temperature); - _mav_put_int16_t(buf, 14, temperature_press_diff); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN); -#else - mavlink_scaled_pressure_t packet; - packet.time_boot_ms = time_boot_ms; - packet.press_abs = press_abs; - packet.press_diff = press_diff; - packet.temperature = temperature; - packet.temperature_press_diff = temperature_press_diff; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SCALED_PRESSURE; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SCALED_PRESSURE_MIN_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE_CRC); -} - -/** - * @brief Encode a scaled_pressure struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param scaled_pressure C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_scaled_pressure_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_scaled_pressure_t* scaled_pressure) -{ - return mavlink_msg_scaled_pressure_pack(system_id, component_id, msg, scaled_pressure->time_boot_ms, scaled_pressure->press_abs, scaled_pressure->press_diff, scaled_pressure->temperature, scaled_pressure->temperature_press_diff); -} - -/** - * @brief Encode a scaled_pressure struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param scaled_pressure C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_scaled_pressure_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_scaled_pressure_t* scaled_pressure) -{ - return mavlink_msg_scaled_pressure_pack_chan(system_id, component_id, chan, msg, scaled_pressure->time_boot_ms, scaled_pressure->press_abs, scaled_pressure->press_diff, scaled_pressure->temperature, scaled_pressure->temperature_press_diff); -} - -/** - * @brief Send a scaled_pressure message - * @param chan MAVLink channel to send the message - * - * @param time_boot_ms [ms] Timestamp (time since system boot). - * @param press_abs [hPa] Absolute pressure - * @param press_diff [hPa] Differential pressure 1 - * @param temperature [cdegC] Absolute pressure temperature - * @param temperature_press_diff [cdegC] Differential pressure temperature (0, if not available). Report values of 0 (or 1) as 1 cdegC. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_scaled_pressure_send(mavlink_channel_t chan, uint32_t time_boot_ms, float press_abs, float press_diff, int16_t temperature, int16_t temperature_press_diff) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SCALED_PRESSURE_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, press_abs); - _mav_put_float(buf, 8, press_diff); - _mav_put_int16_t(buf, 12, temperature); - _mav_put_int16_t(buf, 14, temperature_press_diff); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_PRESSURE, buf, MAVLINK_MSG_ID_SCALED_PRESSURE_MIN_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE_CRC); -#else - mavlink_scaled_pressure_t packet; - packet.time_boot_ms = time_boot_ms; - packet.press_abs = press_abs; - packet.press_diff = press_diff; - packet.temperature = temperature; - packet.temperature_press_diff = temperature_press_diff; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_PRESSURE, (const char *)&packet, MAVLINK_MSG_ID_SCALED_PRESSURE_MIN_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE_CRC); -#endif -} - -/** - * @brief Send a scaled_pressure message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_scaled_pressure_send_struct(mavlink_channel_t chan, const mavlink_scaled_pressure_t* scaled_pressure) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_scaled_pressure_send(chan, scaled_pressure->time_boot_ms, scaled_pressure->press_abs, scaled_pressure->press_diff, scaled_pressure->temperature, scaled_pressure->temperature_press_diff); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_PRESSURE, (const char *)scaled_pressure, MAVLINK_MSG_ID_SCALED_PRESSURE_MIN_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE_CRC); -#endif -} - -#if MAVLINK_MSG_ID_SCALED_PRESSURE_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_scaled_pressure_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, float press_abs, float press_diff, int16_t temperature, int16_t temperature_press_diff) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, press_abs); - _mav_put_float(buf, 8, press_diff); - _mav_put_int16_t(buf, 12, temperature); - _mav_put_int16_t(buf, 14, temperature_press_diff); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_PRESSURE, buf, MAVLINK_MSG_ID_SCALED_PRESSURE_MIN_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE_CRC); -#else - mavlink_scaled_pressure_t *packet = (mavlink_scaled_pressure_t *)msgbuf; - packet->time_boot_ms = time_boot_ms; - packet->press_abs = press_abs; - packet->press_diff = press_diff; - packet->temperature = temperature; - packet->temperature_press_diff = temperature_press_diff; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_PRESSURE, (const char *)packet, MAVLINK_MSG_ID_SCALED_PRESSURE_MIN_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE_CRC); -#endif -} -#endif - -#endif - -// MESSAGE SCALED_PRESSURE UNPACKING - - -/** - * @brief Get field time_boot_ms from scaled_pressure message - * - * @return [ms] Timestamp (time since system boot). - */ -static inline uint32_t mavlink_msg_scaled_pressure_get_time_boot_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field press_abs from scaled_pressure message - * - * @return [hPa] Absolute pressure - */ -static inline float mavlink_msg_scaled_pressure_get_press_abs(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 4); -} - -/** - * @brief Get field press_diff from scaled_pressure message - * - * @return [hPa] Differential pressure 1 - */ -static inline float mavlink_msg_scaled_pressure_get_press_diff(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field temperature from scaled_pressure message - * - * @return [cdegC] Absolute pressure temperature - */ -static inline int16_t mavlink_msg_scaled_pressure_get_temperature(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 12); -} - -/** - * @brief Get field temperature_press_diff from scaled_pressure message - * - * @return [cdegC] Differential pressure temperature (0, if not available). Report values of 0 (or 1) as 1 cdegC. - */ -static inline int16_t mavlink_msg_scaled_pressure_get_temperature_press_diff(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 14); -} - -/** - * @brief Decode a scaled_pressure message into a struct - * - * @param msg The message to decode - * @param scaled_pressure C-struct to decode the message contents into - */ -static inline void mavlink_msg_scaled_pressure_decode(const mavlink_message_t* msg, mavlink_scaled_pressure_t* scaled_pressure) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - scaled_pressure->time_boot_ms = mavlink_msg_scaled_pressure_get_time_boot_ms(msg); - scaled_pressure->press_abs = mavlink_msg_scaled_pressure_get_press_abs(msg); - scaled_pressure->press_diff = mavlink_msg_scaled_pressure_get_press_diff(msg); - scaled_pressure->temperature = mavlink_msg_scaled_pressure_get_temperature(msg); - scaled_pressure->temperature_press_diff = mavlink_msg_scaled_pressure_get_temperature_press_diff(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_SCALED_PRESSURE_LEN? msg->len : MAVLINK_MSG_ID_SCALED_PRESSURE_LEN; - memset(scaled_pressure, 0, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN); - memcpy(scaled_pressure, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_scaled_pressure2.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_scaled_pressure2.h deleted file mode 100644 index 3c4a0f5a..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_scaled_pressure2.h +++ /dev/null @@ -1,313 +0,0 @@ -#pragma once -// MESSAGE SCALED_PRESSURE2 PACKING - -#define MAVLINK_MSG_ID_SCALED_PRESSURE2 137 - - -typedef struct __mavlink_scaled_pressure2_t { - uint32_t time_boot_ms; /*< [ms] Timestamp (time since system boot).*/ - float press_abs; /*< [hPa] Absolute pressure*/ - float press_diff; /*< [hPa] Differential pressure*/ - int16_t temperature; /*< [cdegC] Absolute pressure temperature*/ - int16_t temperature_press_diff; /*< [cdegC] Differential pressure temperature (0, if not available). Report values of 0 (or 1) as 1 cdegC.*/ -} mavlink_scaled_pressure2_t; - -#define MAVLINK_MSG_ID_SCALED_PRESSURE2_LEN 16 -#define MAVLINK_MSG_ID_SCALED_PRESSURE2_MIN_LEN 14 -#define MAVLINK_MSG_ID_137_LEN 16 -#define MAVLINK_MSG_ID_137_MIN_LEN 14 - -#define MAVLINK_MSG_ID_SCALED_PRESSURE2_CRC 195 -#define MAVLINK_MSG_ID_137_CRC 195 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_SCALED_PRESSURE2 { \ - 137, \ - "SCALED_PRESSURE2", \ - 5, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_scaled_pressure2_t, time_boot_ms) }, \ - { "press_abs", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_scaled_pressure2_t, press_abs) }, \ - { "press_diff", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_scaled_pressure2_t, press_diff) }, \ - { "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_scaled_pressure2_t, temperature) }, \ - { "temperature_press_diff", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_scaled_pressure2_t, temperature_press_diff) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_SCALED_PRESSURE2 { \ - "SCALED_PRESSURE2", \ - 5, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_scaled_pressure2_t, time_boot_ms) }, \ - { "press_abs", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_scaled_pressure2_t, press_abs) }, \ - { "press_diff", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_scaled_pressure2_t, press_diff) }, \ - { "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_scaled_pressure2_t, temperature) }, \ - { "temperature_press_diff", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_scaled_pressure2_t, temperature_press_diff) }, \ - } \ -} -#endif - -/** - * @brief Pack a scaled_pressure2 message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param time_boot_ms [ms] Timestamp (time since system boot). - * @param press_abs [hPa] Absolute pressure - * @param press_diff [hPa] Differential pressure - * @param temperature [cdegC] Absolute pressure temperature - * @param temperature_press_diff [cdegC] Differential pressure temperature (0, if not available). Report values of 0 (or 1) as 1 cdegC. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_scaled_pressure2_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint32_t time_boot_ms, float press_abs, float press_diff, int16_t temperature, int16_t temperature_press_diff) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SCALED_PRESSURE2_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, press_abs); - _mav_put_float(buf, 8, press_diff); - _mav_put_int16_t(buf, 12, temperature); - _mav_put_int16_t(buf, 14, temperature_press_diff); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SCALED_PRESSURE2_LEN); -#else - mavlink_scaled_pressure2_t packet; - packet.time_boot_ms = time_boot_ms; - packet.press_abs = press_abs; - packet.press_diff = press_diff; - packet.temperature = temperature; - packet.temperature_press_diff = temperature_press_diff; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SCALED_PRESSURE2_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SCALED_PRESSURE2; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SCALED_PRESSURE2_MIN_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE2_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE2_CRC); -} - -/** - * @brief Pack a scaled_pressure2 message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_boot_ms [ms] Timestamp (time since system boot). - * @param press_abs [hPa] Absolute pressure - * @param press_diff [hPa] Differential pressure - * @param temperature [cdegC] Absolute pressure temperature - * @param temperature_press_diff [cdegC] Differential pressure temperature (0, if not available). Report values of 0 (or 1) as 1 cdegC. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_scaled_pressure2_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint32_t time_boot_ms,float press_abs,float press_diff,int16_t temperature,int16_t temperature_press_diff) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SCALED_PRESSURE2_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, press_abs); - _mav_put_float(buf, 8, press_diff); - _mav_put_int16_t(buf, 12, temperature); - _mav_put_int16_t(buf, 14, temperature_press_diff); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SCALED_PRESSURE2_LEN); -#else - mavlink_scaled_pressure2_t packet; - packet.time_boot_ms = time_boot_ms; - packet.press_abs = press_abs; - packet.press_diff = press_diff; - packet.temperature = temperature; - packet.temperature_press_diff = temperature_press_diff; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SCALED_PRESSURE2_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SCALED_PRESSURE2; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SCALED_PRESSURE2_MIN_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE2_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE2_CRC); -} - -/** - * @brief Encode a scaled_pressure2 struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param scaled_pressure2 C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_scaled_pressure2_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_scaled_pressure2_t* scaled_pressure2) -{ - return mavlink_msg_scaled_pressure2_pack(system_id, component_id, msg, scaled_pressure2->time_boot_ms, scaled_pressure2->press_abs, scaled_pressure2->press_diff, scaled_pressure2->temperature, scaled_pressure2->temperature_press_diff); -} - -/** - * @brief Encode a scaled_pressure2 struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param scaled_pressure2 C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_scaled_pressure2_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_scaled_pressure2_t* scaled_pressure2) -{ - return mavlink_msg_scaled_pressure2_pack_chan(system_id, component_id, chan, msg, scaled_pressure2->time_boot_ms, scaled_pressure2->press_abs, scaled_pressure2->press_diff, scaled_pressure2->temperature, scaled_pressure2->temperature_press_diff); -} - -/** - * @brief Send a scaled_pressure2 message - * @param chan MAVLink channel to send the message - * - * @param time_boot_ms [ms] Timestamp (time since system boot). - * @param press_abs [hPa] Absolute pressure - * @param press_diff [hPa] Differential pressure - * @param temperature [cdegC] Absolute pressure temperature - * @param temperature_press_diff [cdegC] Differential pressure temperature (0, if not available). Report values of 0 (or 1) as 1 cdegC. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_scaled_pressure2_send(mavlink_channel_t chan, uint32_t time_boot_ms, float press_abs, float press_diff, int16_t temperature, int16_t temperature_press_diff) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SCALED_PRESSURE2_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, press_abs); - _mav_put_float(buf, 8, press_diff); - _mav_put_int16_t(buf, 12, temperature); - _mav_put_int16_t(buf, 14, temperature_press_diff); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_PRESSURE2, buf, MAVLINK_MSG_ID_SCALED_PRESSURE2_MIN_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE2_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE2_CRC); -#else - mavlink_scaled_pressure2_t packet; - packet.time_boot_ms = time_boot_ms; - packet.press_abs = press_abs; - packet.press_diff = press_diff; - packet.temperature = temperature; - packet.temperature_press_diff = temperature_press_diff; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_PRESSURE2, (const char *)&packet, MAVLINK_MSG_ID_SCALED_PRESSURE2_MIN_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE2_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE2_CRC); -#endif -} - -/** - * @brief Send a scaled_pressure2 message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_scaled_pressure2_send_struct(mavlink_channel_t chan, const mavlink_scaled_pressure2_t* scaled_pressure2) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_scaled_pressure2_send(chan, scaled_pressure2->time_boot_ms, scaled_pressure2->press_abs, scaled_pressure2->press_diff, scaled_pressure2->temperature, scaled_pressure2->temperature_press_diff); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_PRESSURE2, (const char *)scaled_pressure2, MAVLINK_MSG_ID_SCALED_PRESSURE2_MIN_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE2_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE2_CRC); -#endif -} - -#if MAVLINK_MSG_ID_SCALED_PRESSURE2_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_scaled_pressure2_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, float press_abs, float press_diff, int16_t temperature, int16_t temperature_press_diff) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, press_abs); - _mav_put_float(buf, 8, press_diff); - _mav_put_int16_t(buf, 12, temperature); - _mav_put_int16_t(buf, 14, temperature_press_diff); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_PRESSURE2, buf, MAVLINK_MSG_ID_SCALED_PRESSURE2_MIN_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE2_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE2_CRC); -#else - mavlink_scaled_pressure2_t *packet = (mavlink_scaled_pressure2_t *)msgbuf; - packet->time_boot_ms = time_boot_ms; - packet->press_abs = press_abs; - packet->press_diff = press_diff; - packet->temperature = temperature; - packet->temperature_press_diff = temperature_press_diff; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_PRESSURE2, (const char *)packet, MAVLINK_MSG_ID_SCALED_PRESSURE2_MIN_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE2_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE2_CRC); -#endif -} -#endif - -#endif - -// MESSAGE SCALED_PRESSURE2 UNPACKING - - -/** - * @brief Get field time_boot_ms from scaled_pressure2 message - * - * @return [ms] Timestamp (time since system boot). - */ -static inline uint32_t mavlink_msg_scaled_pressure2_get_time_boot_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field press_abs from scaled_pressure2 message - * - * @return [hPa] Absolute pressure - */ -static inline float mavlink_msg_scaled_pressure2_get_press_abs(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 4); -} - -/** - * @brief Get field press_diff from scaled_pressure2 message - * - * @return [hPa] Differential pressure - */ -static inline float mavlink_msg_scaled_pressure2_get_press_diff(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field temperature from scaled_pressure2 message - * - * @return [cdegC] Absolute pressure temperature - */ -static inline int16_t mavlink_msg_scaled_pressure2_get_temperature(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 12); -} - -/** - * @brief Get field temperature_press_diff from scaled_pressure2 message - * - * @return [cdegC] Differential pressure temperature (0, if not available). Report values of 0 (or 1) as 1 cdegC. - */ -static inline int16_t mavlink_msg_scaled_pressure2_get_temperature_press_diff(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 14); -} - -/** - * @brief Decode a scaled_pressure2 message into a struct - * - * @param msg The message to decode - * @param scaled_pressure2 C-struct to decode the message contents into - */ -static inline void mavlink_msg_scaled_pressure2_decode(const mavlink_message_t* msg, mavlink_scaled_pressure2_t* scaled_pressure2) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - scaled_pressure2->time_boot_ms = mavlink_msg_scaled_pressure2_get_time_boot_ms(msg); - scaled_pressure2->press_abs = mavlink_msg_scaled_pressure2_get_press_abs(msg); - scaled_pressure2->press_diff = mavlink_msg_scaled_pressure2_get_press_diff(msg); - scaled_pressure2->temperature = mavlink_msg_scaled_pressure2_get_temperature(msg); - scaled_pressure2->temperature_press_diff = mavlink_msg_scaled_pressure2_get_temperature_press_diff(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_SCALED_PRESSURE2_LEN? msg->len : MAVLINK_MSG_ID_SCALED_PRESSURE2_LEN; - memset(scaled_pressure2, 0, MAVLINK_MSG_ID_SCALED_PRESSURE2_LEN); - memcpy(scaled_pressure2, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_scaled_pressure3.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_scaled_pressure3.h deleted file mode 100644 index 5c5e9737..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_scaled_pressure3.h +++ /dev/null @@ -1,313 +0,0 @@ -#pragma once -// MESSAGE SCALED_PRESSURE3 PACKING - -#define MAVLINK_MSG_ID_SCALED_PRESSURE3 143 - - -typedef struct __mavlink_scaled_pressure3_t { - uint32_t time_boot_ms; /*< [ms] Timestamp (time since system boot).*/ - float press_abs; /*< [hPa] Absolute pressure*/ - float press_diff; /*< [hPa] Differential pressure*/ - int16_t temperature; /*< [cdegC] Absolute pressure temperature*/ - int16_t temperature_press_diff; /*< [cdegC] Differential pressure temperature (0, if not available). Report values of 0 (or 1) as 1 cdegC.*/ -} mavlink_scaled_pressure3_t; - -#define MAVLINK_MSG_ID_SCALED_PRESSURE3_LEN 16 -#define MAVLINK_MSG_ID_SCALED_PRESSURE3_MIN_LEN 14 -#define MAVLINK_MSG_ID_143_LEN 16 -#define MAVLINK_MSG_ID_143_MIN_LEN 14 - -#define MAVLINK_MSG_ID_SCALED_PRESSURE3_CRC 131 -#define MAVLINK_MSG_ID_143_CRC 131 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_SCALED_PRESSURE3 { \ - 143, \ - "SCALED_PRESSURE3", \ - 5, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_scaled_pressure3_t, time_boot_ms) }, \ - { "press_abs", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_scaled_pressure3_t, press_abs) }, \ - { "press_diff", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_scaled_pressure3_t, press_diff) }, \ - { "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_scaled_pressure3_t, temperature) }, \ - { "temperature_press_diff", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_scaled_pressure3_t, temperature_press_diff) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_SCALED_PRESSURE3 { \ - "SCALED_PRESSURE3", \ - 5, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_scaled_pressure3_t, time_boot_ms) }, \ - { "press_abs", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_scaled_pressure3_t, press_abs) }, \ - { "press_diff", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_scaled_pressure3_t, press_diff) }, \ - { "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_scaled_pressure3_t, temperature) }, \ - { "temperature_press_diff", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_scaled_pressure3_t, temperature_press_diff) }, \ - } \ -} -#endif - -/** - * @brief Pack a scaled_pressure3 message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param time_boot_ms [ms] Timestamp (time since system boot). - * @param press_abs [hPa] Absolute pressure - * @param press_diff [hPa] Differential pressure - * @param temperature [cdegC] Absolute pressure temperature - * @param temperature_press_diff [cdegC] Differential pressure temperature (0, if not available). Report values of 0 (or 1) as 1 cdegC. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_scaled_pressure3_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint32_t time_boot_ms, float press_abs, float press_diff, int16_t temperature, int16_t temperature_press_diff) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SCALED_PRESSURE3_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, press_abs); - _mav_put_float(buf, 8, press_diff); - _mav_put_int16_t(buf, 12, temperature); - _mav_put_int16_t(buf, 14, temperature_press_diff); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SCALED_PRESSURE3_LEN); -#else - mavlink_scaled_pressure3_t packet; - packet.time_boot_ms = time_boot_ms; - packet.press_abs = press_abs; - packet.press_diff = press_diff; - packet.temperature = temperature; - packet.temperature_press_diff = temperature_press_diff; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SCALED_PRESSURE3_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SCALED_PRESSURE3; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SCALED_PRESSURE3_MIN_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE3_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE3_CRC); -} - -/** - * @brief Pack a scaled_pressure3 message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_boot_ms [ms] Timestamp (time since system boot). - * @param press_abs [hPa] Absolute pressure - * @param press_diff [hPa] Differential pressure - * @param temperature [cdegC] Absolute pressure temperature - * @param temperature_press_diff [cdegC] Differential pressure temperature (0, if not available). Report values of 0 (or 1) as 1 cdegC. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_scaled_pressure3_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint32_t time_boot_ms,float press_abs,float press_diff,int16_t temperature,int16_t temperature_press_diff) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SCALED_PRESSURE3_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, press_abs); - _mav_put_float(buf, 8, press_diff); - _mav_put_int16_t(buf, 12, temperature); - _mav_put_int16_t(buf, 14, temperature_press_diff); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SCALED_PRESSURE3_LEN); -#else - mavlink_scaled_pressure3_t packet; - packet.time_boot_ms = time_boot_ms; - packet.press_abs = press_abs; - packet.press_diff = press_diff; - packet.temperature = temperature; - packet.temperature_press_diff = temperature_press_diff; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SCALED_PRESSURE3_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SCALED_PRESSURE3; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SCALED_PRESSURE3_MIN_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE3_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE3_CRC); -} - -/** - * @brief Encode a scaled_pressure3 struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param scaled_pressure3 C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_scaled_pressure3_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_scaled_pressure3_t* scaled_pressure3) -{ - return mavlink_msg_scaled_pressure3_pack(system_id, component_id, msg, scaled_pressure3->time_boot_ms, scaled_pressure3->press_abs, scaled_pressure3->press_diff, scaled_pressure3->temperature, scaled_pressure3->temperature_press_diff); -} - -/** - * @brief Encode a scaled_pressure3 struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param scaled_pressure3 C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_scaled_pressure3_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_scaled_pressure3_t* scaled_pressure3) -{ - return mavlink_msg_scaled_pressure3_pack_chan(system_id, component_id, chan, msg, scaled_pressure3->time_boot_ms, scaled_pressure3->press_abs, scaled_pressure3->press_diff, scaled_pressure3->temperature, scaled_pressure3->temperature_press_diff); -} - -/** - * @brief Send a scaled_pressure3 message - * @param chan MAVLink channel to send the message - * - * @param time_boot_ms [ms] Timestamp (time since system boot). - * @param press_abs [hPa] Absolute pressure - * @param press_diff [hPa] Differential pressure - * @param temperature [cdegC] Absolute pressure temperature - * @param temperature_press_diff [cdegC] Differential pressure temperature (0, if not available). Report values of 0 (or 1) as 1 cdegC. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_scaled_pressure3_send(mavlink_channel_t chan, uint32_t time_boot_ms, float press_abs, float press_diff, int16_t temperature, int16_t temperature_press_diff) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SCALED_PRESSURE3_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, press_abs); - _mav_put_float(buf, 8, press_diff); - _mav_put_int16_t(buf, 12, temperature); - _mav_put_int16_t(buf, 14, temperature_press_diff); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_PRESSURE3, buf, MAVLINK_MSG_ID_SCALED_PRESSURE3_MIN_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE3_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE3_CRC); -#else - mavlink_scaled_pressure3_t packet; - packet.time_boot_ms = time_boot_ms; - packet.press_abs = press_abs; - packet.press_diff = press_diff; - packet.temperature = temperature; - packet.temperature_press_diff = temperature_press_diff; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_PRESSURE3, (const char *)&packet, MAVLINK_MSG_ID_SCALED_PRESSURE3_MIN_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE3_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE3_CRC); -#endif -} - -/** - * @brief Send a scaled_pressure3 message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_scaled_pressure3_send_struct(mavlink_channel_t chan, const mavlink_scaled_pressure3_t* scaled_pressure3) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_scaled_pressure3_send(chan, scaled_pressure3->time_boot_ms, scaled_pressure3->press_abs, scaled_pressure3->press_diff, scaled_pressure3->temperature, scaled_pressure3->temperature_press_diff); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_PRESSURE3, (const char *)scaled_pressure3, MAVLINK_MSG_ID_SCALED_PRESSURE3_MIN_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE3_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE3_CRC); -#endif -} - -#if MAVLINK_MSG_ID_SCALED_PRESSURE3_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_scaled_pressure3_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, float press_abs, float press_diff, int16_t temperature, int16_t temperature_press_diff) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, press_abs); - _mav_put_float(buf, 8, press_diff); - _mav_put_int16_t(buf, 12, temperature); - _mav_put_int16_t(buf, 14, temperature_press_diff); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_PRESSURE3, buf, MAVLINK_MSG_ID_SCALED_PRESSURE3_MIN_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE3_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE3_CRC); -#else - mavlink_scaled_pressure3_t *packet = (mavlink_scaled_pressure3_t *)msgbuf; - packet->time_boot_ms = time_boot_ms; - packet->press_abs = press_abs; - packet->press_diff = press_diff; - packet->temperature = temperature; - packet->temperature_press_diff = temperature_press_diff; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_PRESSURE3, (const char *)packet, MAVLINK_MSG_ID_SCALED_PRESSURE3_MIN_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE3_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE3_CRC); -#endif -} -#endif - -#endif - -// MESSAGE SCALED_PRESSURE3 UNPACKING - - -/** - * @brief Get field time_boot_ms from scaled_pressure3 message - * - * @return [ms] Timestamp (time since system boot). - */ -static inline uint32_t mavlink_msg_scaled_pressure3_get_time_boot_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field press_abs from scaled_pressure3 message - * - * @return [hPa] Absolute pressure - */ -static inline float mavlink_msg_scaled_pressure3_get_press_abs(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 4); -} - -/** - * @brief Get field press_diff from scaled_pressure3 message - * - * @return [hPa] Differential pressure - */ -static inline float mavlink_msg_scaled_pressure3_get_press_diff(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field temperature from scaled_pressure3 message - * - * @return [cdegC] Absolute pressure temperature - */ -static inline int16_t mavlink_msg_scaled_pressure3_get_temperature(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 12); -} - -/** - * @brief Get field temperature_press_diff from scaled_pressure3 message - * - * @return [cdegC] Differential pressure temperature (0, if not available). Report values of 0 (or 1) as 1 cdegC. - */ -static inline int16_t mavlink_msg_scaled_pressure3_get_temperature_press_diff(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 14); -} - -/** - * @brief Decode a scaled_pressure3 message into a struct - * - * @param msg The message to decode - * @param scaled_pressure3 C-struct to decode the message contents into - */ -static inline void mavlink_msg_scaled_pressure3_decode(const mavlink_message_t* msg, mavlink_scaled_pressure3_t* scaled_pressure3) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - scaled_pressure3->time_boot_ms = mavlink_msg_scaled_pressure3_get_time_boot_ms(msg); - scaled_pressure3->press_abs = mavlink_msg_scaled_pressure3_get_press_abs(msg); - scaled_pressure3->press_diff = mavlink_msg_scaled_pressure3_get_press_diff(msg); - scaled_pressure3->temperature = mavlink_msg_scaled_pressure3_get_temperature(msg); - scaled_pressure3->temperature_press_diff = mavlink_msg_scaled_pressure3_get_temperature_press_diff(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_SCALED_PRESSURE3_LEN? msg->len : MAVLINK_MSG_ID_SCALED_PRESSURE3_LEN; - memset(scaled_pressure3, 0, MAVLINK_MSG_ID_SCALED_PRESSURE3_LEN); - memcpy(scaled_pressure3, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_serial_control.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_serial_control.h deleted file mode 100644 index 64b190af..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_serial_control.h +++ /dev/null @@ -1,380 +0,0 @@ -#pragma once -// MESSAGE SERIAL_CONTROL PACKING - -#define MAVLINK_MSG_ID_SERIAL_CONTROL 126 - - -typedef struct __mavlink_serial_control_t { - uint32_t baudrate; /*< [bits/s] Baudrate of transfer. Zero means no change.*/ - uint16_t timeout; /*< [ms] Timeout for reply data*/ - uint8_t device; /*< Serial control device type.*/ - uint8_t flags; /*< Bitmap of serial control flags.*/ - uint8_t count; /*< [bytes] how many bytes in this transfer*/ - uint8_t data[70]; /*< serial data*/ - uint8_t target_system; /*< System ID*/ - uint8_t target_component; /*< Component ID*/ -} mavlink_serial_control_t; - -#define MAVLINK_MSG_ID_SERIAL_CONTROL_LEN 81 -#define MAVLINK_MSG_ID_SERIAL_CONTROL_MIN_LEN 79 -#define MAVLINK_MSG_ID_126_LEN 81 -#define MAVLINK_MSG_ID_126_MIN_LEN 79 - -#define MAVLINK_MSG_ID_SERIAL_CONTROL_CRC 220 -#define MAVLINK_MSG_ID_126_CRC 220 - -#define MAVLINK_MSG_SERIAL_CONTROL_FIELD_DATA_LEN 70 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_SERIAL_CONTROL { \ - 126, \ - "SERIAL_CONTROL", \ - 8, \ - { { "device", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_serial_control_t, device) }, \ - { "flags", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_serial_control_t, flags) }, \ - { "timeout", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_serial_control_t, timeout) }, \ - { "baudrate", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_serial_control_t, baudrate) }, \ - { "count", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_serial_control_t, count) }, \ - { "data", NULL, MAVLINK_TYPE_UINT8_T, 70, 9, offsetof(mavlink_serial_control_t, data) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 79, offsetof(mavlink_serial_control_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 80, offsetof(mavlink_serial_control_t, target_component) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_SERIAL_CONTROL { \ - "SERIAL_CONTROL", \ - 8, \ - { { "device", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_serial_control_t, device) }, \ - { "flags", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_serial_control_t, flags) }, \ - { "timeout", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_serial_control_t, timeout) }, \ - { "baudrate", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_serial_control_t, baudrate) }, \ - { "count", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_serial_control_t, count) }, \ - { "data", NULL, MAVLINK_TYPE_UINT8_T, 70, 9, offsetof(mavlink_serial_control_t, data) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 79, offsetof(mavlink_serial_control_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 80, offsetof(mavlink_serial_control_t, target_component) }, \ - } \ -} -#endif - -/** - * @brief Pack a serial_control message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param device Serial control device type. - * @param flags Bitmap of serial control flags. - * @param timeout [ms] Timeout for reply data - * @param baudrate [bits/s] Baudrate of transfer. Zero means no change. - * @param count [bytes] how many bytes in this transfer - * @param data serial data - * @param target_system System ID - * @param target_component Component ID - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_serial_control_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t device, uint8_t flags, uint16_t timeout, uint32_t baudrate, uint8_t count, const uint8_t *data, uint8_t target_system, uint8_t target_component) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SERIAL_CONTROL_LEN]; - _mav_put_uint32_t(buf, 0, baudrate); - _mav_put_uint16_t(buf, 4, timeout); - _mav_put_uint8_t(buf, 6, device); - _mav_put_uint8_t(buf, 7, flags); - _mav_put_uint8_t(buf, 8, count); - _mav_put_uint8_t(buf, 79, target_system); - _mav_put_uint8_t(buf, 80, target_component); - _mav_put_uint8_t_array(buf, 9, data, 70); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN); -#else - mavlink_serial_control_t packet; - packet.baudrate = baudrate; - packet.timeout = timeout; - packet.device = device; - packet.flags = flags; - packet.count = count; - packet.target_system = target_system; - packet.target_component = target_component; - mav_array_memcpy(packet.data, data, sizeof(uint8_t)*70); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SERIAL_CONTROL; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SERIAL_CONTROL_MIN_LEN, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN, MAVLINK_MSG_ID_SERIAL_CONTROL_CRC); -} - -/** - * @brief Pack a serial_control message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param device Serial control device type. - * @param flags Bitmap of serial control flags. - * @param timeout [ms] Timeout for reply data - * @param baudrate [bits/s] Baudrate of transfer. Zero means no change. - * @param count [bytes] how many bytes in this transfer - * @param data serial data - * @param target_system System ID - * @param target_component Component ID - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_serial_control_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t device,uint8_t flags,uint16_t timeout,uint32_t baudrate,uint8_t count,const uint8_t *data,uint8_t target_system,uint8_t target_component) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SERIAL_CONTROL_LEN]; - _mav_put_uint32_t(buf, 0, baudrate); - _mav_put_uint16_t(buf, 4, timeout); - _mav_put_uint8_t(buf, 6, device); - _mav_put_uint8_t(buf, 7, flags); - _mav_put_uint8_t(buf, 8, count); - _mav_put_uint8_t(buf, 79, target_system); - _mav_put_uint8_t(buf, 80, target_component); - _mav_put_uint8_t_array(buf, 9, data, 70); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN); -#else - mavlink_serial_control_t packet; - packet.baudrate = baudrate; - packet.timeout = timeout; - packet.device = device; - packet.flags = flags; - packet.count = count; - packet.target_system = target_system; - packet.target_component = target_component; - mav_array_memcpy(packet.data, data, sizeof(uint8_t)*70); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SERIAL_CONTROL; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SERIAL_CONTROL_MIN_LEN, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN, MAVLINK_MSG_ID_SERIAL_CONTROL_CRC); -} - -/** - * @brief Encode a serial_control struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param serial_control C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_serial_control_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_serial_control_t* serial_control) -{ - return mavlink_msg_serial_control_pack(system_id, component_id, msg, serial_control->device, serial_control->flags, serial_control->timeout, serial_control->baudrate, serial_control->count, serial_control->data, serial_control->target_system, serial_control->target_component); -} - -/** - * @brief Encode a serial_control struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param serial_control C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_serial_control_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_serial_control_t* serial_control) -{ - return mavlink_msg_serial_control_pack_chan(system_id, component_id, chan, msg, serial_control->device, serial_control->flags, serial_control->timeout, serial_control->baudrate, serial_control->count, serial_control->data, serial_control->target_system, serial_control->target_component); -} - -/** - * @brief Send a serial_control message - * @param chan MAVLink channel to send the message - * - * @param device Serial control device type. - * @param flags Bitmap of serial control flags. - * @param timeout [ms] Timeout for reply data - * @param baudrate [bits/s] Baudrate of transfer. Zero means no change. - * @param count [bytes] how many bytes in this transfer - * @param data serial data - * @param target_system System ID - * @param target_component Component ID - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_serial_control_send(mavlink_channel_t chan, uint8_t device, uint8_t flags, uint16_t timeout, uint32_t baudrate, uint8_t count, const uint8_t *data, uint8_t target_system, uint8_t target_component) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SERIAL_CONTROL_LEN]; - _mav_put_uint32_t(buf, 0, baudrate); - _mav_put_uint16_t(buf, 4, timeout); - _mav_put_uint8_t(buf, 6, device); - _mav_put_uint8_t(buf, 7, flags); - _mav_put_uint8_t(buf, 8, count); - _mav_put_uint8_t(buf, 79, target_system); - _mav_put_uint8_t(buf, 80, target_component); - _mav_put_uint8_t_array(buf, 9, data, 70); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_CONTROL, buf, MAVLINK_MSG_ID_SERIAL_CONTROL_MIN_LEN, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN, MAVLINK_MSG_ID_SERIAL_CONTROL_CRC); -#else - mavlink_serial_control_t packet; - packet.baudrate = baudrate; - packet.timeout = timeout; - packet.device = device; - packet.flags = flags; - packet.count = count; - packet.target_system = target_system; - packet.target_component = target_component; - mav_array_memcpy(packet.data, data, sizeof(uint8_t)*70); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_CONTROL, (const char *)&packet, MAVLINK_MSG_ID_SERIAL_CONTROL_MIN_LEN, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN, MAVLINK_MSG_ID_SERIAL_CONTROL_CRC); -#endif -} - -/** - * @brief Send a serial_control message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_serial_control_send_struct(mavlink_channel_t chan, const mavlink_serial_control_t* serial_control) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_serial_control_send(chan, serial_control->device, serial_control->flags, serial_control->timeout, serial_control->baudrate, serial_control->count, serial_control->data, serial_control->target_system, serial_control->target_component); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_CONTROL, (const char *)serial_control, MAVLINK_MSG_ID_SERIAL_CONTROL_MIN_LEN, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN, MAVLINK_MSG_ID_SERIAL_CONTROL_CRC); -#endif -} - -#if MAVLINK_MSG_ID_SERIAL_CONTROL_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_serial_control_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t device, uint8_t flags, uint16_t timeout, uint32_t baudrate, uint8_t count, const uint8_t *data, uint8_t target_system, uint8_t target_component) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, baudrate); - _mav_put_uint16_t(buf, 4, timeout); - _mav_put_uint8_t(buf, 6, device); - _mav_put_uint8_t(buf, 7, flags); - _mav_put_uint8_t(buf, 8, count); - _mav_put_uint8_t(buf, 79, target_system); - _mav_put_uint8_t(buf, 80, target_component); - _mav_put_uint8_t_array(buf, 9, data, 70); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_CONTROL, buf, MAVLINK_MSG_ID_SERIAL_CONTROL_MIN_LEN, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN, MAVLINK_MSG_ID_SERIAL_CONTROL_CRC); -#else - mavlink_serial_control_t *packet = (mavlink_serial_control_t *)msgbuf; - packet->baudrate = baudrate; - packet->timeout = timeout; - packet->device = device; - packet->flags = flags; - packet->count = count; - packet->target_system = target_system; - packet->target_component = target_component; - mav_array_memcpy(packet->data, data, sizeof(uint8_t)*70); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_CONTROL, (const char *)packet, MAVLINK_MSG_ID_SERIAL_CONTROL_MIN_LEN, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN, MAVLINK_MSG_ID_SERIAL_CONTROL_CRC); -#endif -} -#endif - -#endif - -// MESSAGE SERIAL_CONTROL UNPACKING - - -/** - * @brief Get field device from serial_control message - * - * @return Serial control device type. - */ -static inline uint8_t mavlink_msg_serial_control_get_device(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 6); -} - -/** - * @brief Get field flags from serial_control message - * - * @return Bitmap of serial control flags. - */ -static inline uint8_t mavlink_msg_serial_control_get_flags(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 7); -} - -/** - * @brief Get field timeout from serial_control message - * - * @return [ms] Timeout for reply data - */ -static inline uint16_t mavlink_msg_serial_control_get_timeout(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 4); -} - -/** - * @brief Get field baudrate from serial_control message - * - * @return [bits/s] Baudrate of transfer. Zero means no change. - */ -static inline uint32_t mavlink_msg_serial_control_get_baudrate(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field count from serial_control message - * - * @return [bytes] how many bytes in this transfer - */ -static inline uint8_t mavlink_msg_serial_control_get_count(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 8); -} - -/** - * @brief Get field data from serial_control message - * - * @return serial data - */ -static inline uint16_t mavlink_msg_serial_control_get_data(const mavlink_message_t* msg, uint8_t *data) -{ - return _MAV_RETURN_uint8_t_array(msg, data, 70, 9); -} - -/** - * @brief Get field target_system from serial_control message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_serial_control_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 79); -} - -/** - * @brief Get field target_component from serial_control message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_serial_control_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 80); -} - -/** - * @brief Decode a serial_control message into a struct - * - * @param msg The message to decode - * @param serial_control C-struct to decode the message contents into - */ -static inline void mavlink_msg_serial_control_decode(const mavlink_message_t* msg, mavlink_serial_control_t* serial_control) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - serial_control->baudrate = mavlink_msg_serial_control_get_baudrate(msg); - serial_control->timeout = mavlink_msg_serial_control_get_timeout(msg); - serial_control->device = mavlink_msg_serial_control_get_device(msg); - serial_control->flags = mavlink_msg_serial_control_get_flags(msg); - serial_control->count = mavlink_msg_serial_control_get_count(msg); - mavlink_msg_serial_control_get_data(msg, serial_control->data); - serial_control->target_system = mavlink_msg_serial_control_get_target_system(msg); - serial_control->target_component = mavlink_msg_serial_control_get_target_component(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_SERIAL_CONTROL_LEN? msg->len : MAVLINK_MSG_ID_SERIAL_CONTROL_LEN; - memset(serial_control, 0, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN); - memcpy(serial_control, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_servo_output_raw.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_servo_output_raw.h deleted file mode 100644 index d1a5bb65..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_servo_output_raw.h +++ /dev/null @@ -1,638 +0,0 @@ -#pragma once -// MESSAGE SERVO_OUTPUT_RAW PACKING - -#define MAVLINK_MSG_ID_SERVO_OUTPUT_RAW 36 - -MAVPACKED( -typedef struct __mavlink_servo_output_raw_t { - uint32_t time_usec; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/ - uint16_t servo1_raw; /*< [us] Servo output 1 value*/ - uint16_t servo2_raw; /*< [us] Servo output 2 value*/ - uint16_t servo3_raw; /*< [us] Servo output 3 value*/ - uint16_t servo4_raw; /*< [us] Servo output 4 value*/ - uint16_t servo5_raw; /*< [us] Servo output 5 value*/ - uint16_t servo6_raw; /*< [us] Servo output 6 value*/ - uint16_t servo7_raw; /*< [us] Servo output 7 value*/ - uint16_t servo8_raw; /*< [us] Servo output 8 value*/ - uint8_t port; /*< Servo output port (set of 8 outputs = 1 port). Flight stacks running on Pixhawk should use: 0 = MAIN, 1 = AUX.*/ - uint16_t servo9_raw; /*< [us] Servo output 9 value*/ - uint16_t servo10_raw; /*< [us] Servo output 10 value*/ - uint16_t servo11_raw; /*< [us] Servo output 11 value*/ - uint16_t servo12_raw; /*< [us] Servo output 12 value*/ - uint16_t servo13_raw; /*< [us] Servo output 13 value*/ - uint16_t servo14_raw; /*< [us] Servo output 14 value*/ - uint16_t servo15_raw; /*< [us] Servo output 15 value*/ - uint16_t servo16_raw; /*< [us] Servo output 16 value*/ -}) mavlink_servo_output_raw_t; - -#define MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN 37 -#define MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_MIN_LEN 21 -#define MAVLINK_MSG_ID_36_LEN 37 -#define MAVLINK_MSG_ID_36_MIN_LEN 21 - -#define MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_CRC 222 -#define MAVLINK_MSG_ID_36_CRC 222 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_SERVO_OUTPUT_RAW { \ - 36, \ - "SERVO_OUTPUT_RAW", \ - 18, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_servo_output_raw_t, time_usec) }, \ - { "port", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_servo_output_raw_t, port) }, \ - { "servo1_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_servo_output_raw_t, servo1_raw) }, \ - { "servo2_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_servo_output_raw_t, servo2_raw) }, \ - { "servo3_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_servo_output_raw_t, servo3_raw) }, \ - { "servo4_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_servo_output_raw_t, servo4_raw) }, \ - { "servo5_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_servo_output_raw_t, servo5_raw) }, \ - { "servo6_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_servo_output_raw_t, servo6_raw) }, \ - { "servo7_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_servo_output_raw_t, servo7_raw) }, \ - { "servo8_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_servo_output_raw_t, servo8_raw) }, \ - { "servo9_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 21, offsetof(mavlink_servo_output_raw_t, servo9_raw) }, \ - { "servo10_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 23, offsetof(mavlink_servo_output_raw_t, servo10_raw) }, \ - { "servo11_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 25, offsetof(mavlink_servo_output_raw_t, servo11_raw) }, \ - { "servo12_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 27, offsetof(mavlink_servo_output_raw_t, servo12_raw) }, \ - { "servo13_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 29, offsetof(mavlink_servo_output_raw_t, servo13_raw) }, \ - { "servo14_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 31, offsetof(mavlink_servo_output_raw_t, servo14_raw) }, \ - { "servo15_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 33, offsetof(mavlink_servo_output_raw_t, servo15_raw) }, \ - { "servo16_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 35, offsetof(mavlink_servo_output_raw_t, servo16_raw) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_SERVO_OUTPUT_RAW { \ - "SERVO_OUTPUT_RAW", \ - 18, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_servo_output_raw_t, time_usec) }, \ - { "port", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_servo_output_raw_t, port) }, \ - { "servo1_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_servo_output_raw_t, servo1_raw) }, \ - { "servo2_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_servo_output_raw_t, servo2_raw) }, \ - { "servo3_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_servo_output_raw_t, servo3_raw) }, \ - { "servo4_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_servo_output_raw_t, servo4_raw) }, \ - { "servo5_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_servo_output_raw_t, servo5_raw) }, \ - { "servo6_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_servo_output_raw_t, servo6_raw) }, \ - { "servo7_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_servo_output_raw_t, servo7_raw) }, \ - { "servo8_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_servo_output_raw_t, servo8_raw) }, \ - { "servo9_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 21, offsetof(mavlink_servo_output_raw_t, servo9_raw) }, \ - { "servo10_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 23, offsetof(mavlink_servo_output_raw_t, servo10_raw) }, \ - { "servo11_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 25, offsetof(mavlink_servo_output_raw_t, servo11_raw) }, \ - { "servo12_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 27, offsetof(mavlink_servo_output_raw_t, servo12_raw) }, \ - { "servo13_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 29, offsetof(mavlink_servo_output_raw_t, servo13_raw) }, \ - { "servo14_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 31, offsetof(mavlink_servo_output_raw_t, servo14_raw) }, \ - { "servo15_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 33, offsetof(mavlink_servo_output_raw_t, servo15_raw) }, \ - { "servo16_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 35, offsetof(mavlink_servo_output_raw_t, servo16_raw) }, \ - } \ -} -#endif - -/** - * @brief Pack a servo_output_raw message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @param port Servo output port (set of 8 outputs = 1 port). Flight stacks running on Pixhawk should use: 0 = MAIN, 1 = AUX. - * @param servo1_raw [us] Servo output 1 value - * @param servo2_raw [us] Servo output 2 value - * @param servo3_raw [us] Servo output 3 value - * @param servo4_raw [us] Servo output 4 value - * @param servo5_raw [us] Servo output 5 value - * @param servo6_raw [us] Servo output 6 value - * @param servo7_raw [us] Servo output 7 value - * @param servo8_raw [us] Servo output 8 value - * @param servo9_raw [us] Servo output 9 value - * @param servo10_raw [us] Servo output 10 value - * @param servo11_raw [us] Servo output 11 value - * @param servo12_raw [us] Servo output 12 value - * @param servo13_raw [us] Servo output 13 value - * @param servo14_raw [us] Servo output 14 value - * @param servo15_raw [us] Servo output 15 value - * @param servo16_raw [us] Servo output 16 value - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_servo_output_raw_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint32_t time_usec, uint8_t port, uint16_t servo1_raw, uint16_t servo2_raw, uint16_t servo3_raw, uint16_t servo4_raw, uint16_t servo5_raw, uint16_t servo6_raw, uint16_t servo7_raw, uint16_t servo8_raw, uint16_t servo9_raw, uint16_t servo10_raw, uint16_t servo11_raw, uint16_t servo12_raw, uint16_t servo13_raw, uint16_t servo14_raw, uint16_t servo15_raw, uint16_t servo16_raw) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN]; - _mav_put_uint32_t(buf, 0, time_usec); - _mav_put_uint16_t(buf, 4, servo1_raw); - _mav_put_uint16_t(buf, 6, servo2_raw); - _mav_put_uint16_t(buf, 8, servo3_raw); - _mav_put_uint16_t(buf, 10, servo4_raw); - _mav_put_uint16_t(buf, 12, servo5_raw); - _mav_put_uint16_t(buf, 14, servo6_raw); - _mav_put_uint16_t(buf, 16, servo7_raw); - _mav_put_uint16_t(buf, 18, servo8_raw); - _mav_put_uint8_t(buf, 20, port); - _mav_put_uint16_t(buf, 21, servo9_raw); - _mav_put_uint16_t(buf, 23, servo10_raw); - _mav_put_uint16_t(buf, 25, servo11_raw); - _mav_put_uint16_t(buf, 27, servo12_raw); - _mav_put_uint16_t(buf, 29, servo13_raw); - _mav_put_uint16_t(buf, 31, servo14_raw); - _mav_put_uint16_t(buf, 33, servo15_raw); - _mav_put_uint16_t(buf, 35, servo16_raw); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN); -#else - mavlink_servo_output_raw_t packet; - packet.time_usec = time_usec; - packet.servo1_raw = servo1_raw; - packet.servo2_raw = servo2_raw; - packet.servo3_raw = servo3_raw; - packet.servo4_raw = servo4_raw; - packet.servo5_raw = servo5_raw; - packet.servo6_raw = servo6_raw; - packet.servo7_raw = servo7_raw; - packet.servo8_raw = servo8_raw; - packet.port = port; - packet.servo9_raw = servo9_raw; - packet.servo10_raw = servo10_raw; - packet.servo11_raw = servo11_raw; - packet.servo12_raw = servo12_raw; - packet.servo13_raw = servo13_raw; - packet.servo14_raw = servo14_raw; - packet.servo15_raw = servo15_raw; - packet.servo16_raw = servo16_raw; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SERVO_OUTPUT_RAW; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_MIN_LEN, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_CRC); -} - -/** - * @brief Pack a servo_output_raw message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @param port Servo output port (set of 8 outputs = 1 port). Flight stacks running on Pixhawk should use: 0 = MAIN, 1 = AUX. - * @param servo1_raw [us] Servo output 1 value - * @param servo2_raw [us] Servo output 2 value - * @param servo3_raw [us] Servo output 3 value - * @param servo4_raw [us] Servo output 4 value - * @param servo5_raw [us] Servo output 5 value - * @param servo6_raw [us] Servo output 6 value - * @param servo7_raw [us] Servo output 7 value - * @param servo8_raw [us] Servo output 8 value - * @param servo9_raw [us] Servo output 9 value - * @param servo10_raw [us] Servo output 10 value - * @param servo11_raw [us] Servo output 11 value - * @param servo12_raw [us] Servo output 12 value - * @param servo13_raw [us] Servo output 13 value - * @param servo14_raw [us] Servo output 14 value - * @param servo15_raw [us] Servo output 15 value - * @param servo16_raw [us] Servo output 16 value - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_servo_output_raw_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint32_t time_usec,uint8_t port,uint16_t servo1_raw,uint16_t servo2_raw,uint16_t servo3_raw,uint16_t servo4_raw,uint16_t servo5_raw,uint16_t servo6_raw,uint16_t servo7_raw,uint16_t servo8_raw,uint16_t servo9_raw,uint16_t servo10_raw,uint16_t servo11_raw,uint16_t servo12_raw,uint16_t servo13_raw,uint16_t servo14_raw,uint16_t servo15_raw,uint16_t servo16_raw) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN]; - _mav_put_uint32_t(buf, 0, time_usec); - _mav_put_uint16_t(buf, 4, servo1_raw); - _mav_put_uint16_t(buf, 6, servo2_raw); - _mav_put_uint16_t(buf, 8, servo3_raw); - _mav_put_uint16_t(buf, 10, servo4_raw); - _mav_put_uint16_t(buf, 12, servo5_raw); - _mav_put_uint16_t(buf, 14, servo6_raw); - _mav_put_uint16_t(buf, 16, servo7_raw); - _mav_put_uint16_t(buf, 18, servo8_raw); - _mav_put_uint8_t(buf, 20, port); - _mav_put_uint16_t(buf, 21, servo9_raw); - _mav_put_uint16_t(buf, 23, servo10_raw); - _mav_put_uint16_t(buf, 25, servo11_raw); - _mav_put_uint16_t(buf, 27, servo12_raw); - _mav_put_uint16_t(buf, 29, servo13_raw); - _mav_put_uint16_t(buf, 31, servo14_raw); - _mav_put_uint16_t(buf, 33, servo15_raw); - _mav_put_uint16_t(buf, 35, servo16_raw); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN); -#else - mavlink_servo_output_raw_t packet; - packet.time_usec = time_usec; - packet.servo1_raw = servo1_raw; - packet.servo2_raw = servo2_raw; - packet.servo3_raw = servo3_raw; - packet.servo4_raw = servo4_raw; - packet.servo5_raw = servo5_raw; - packet.servo6_raw = servo6_raw; - packet.servo7_raw = servo7_raw; - packet.servo8_raw = servo8_raw; - packet.port = port; - packet.servo9_raw = servo9_raw; - packet.servo10_raw = servo10_raw; - packet.servo11_raw = servo11_raw; - packet.servo12_raw = servo12_raw; - packet.servo13_raw = servo13_raw; - packet.servo14_raw = servo14_raw; - packet.servo15_raw = servo15_raw; - packet.servo16_raw = servo16_raw; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SERVO_OUTPUT_RAW; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_MIN_LEN, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_CRC); -} - -/** - * @brief Encode a servo_output_raw struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param servo_output_raw C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_servo_output_raw_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_servo_output_raw_t* servo_output_raw) -{ - return mavlink_msg_servo_output_raw_pack(system_id, component_id, msg, servo_output_raw->time_usec, servo_output_raw->port, servo_output_raw->servo1_raw, servo_output_raw->servo2_raw, servo_output_raw->servo3_raw, servo_output_raw->servo4_raw, servo_output_raw->servo5_raw, servo_output_raw->servo6_raw, servo_output_raw->servo7_raw, servo_output_raw->servo8_raw, servo_output_raw->servo9_raw, servo_output_raw->servo10_raw, servo_output_raw->servo11_raw, servo_output_raw->servo12_raw, servo_output_raw->servo13_raw, servo_output_raw->servo14_raw, servo_output_raw->servo15_raw, servo_output_raw->servo16_raw); -} - -/** - * @brief Encode a servo_output_raw struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param servo_output_raw C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_servo_output_raw_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_servo_output_raw_t* servo_output_raw) -{ - return mavlink_msg_servo_output_raw_pack_chan(system_id, component_id, chan, msg, servo_output_raw->time_usec, servo_output_raw->port, servo_output_raw->servo1_raw, servo_output_raw->servo2_raw, servo_output_raw->servo3_raw, servo_output_raw->servo4_raw, servo_output_raw->servo5_raw, servo_output_raw->servo6_raw, servo_output_raw->servo7_raw, servo_output_raw->servo8_raw, servo_output_raw->servo9_raw, servo_output_raw->servo10_raw, servo_output_raw->servo11_raw, servo_output_raw->servo12_raw, servo_output_raw->servo13_raw, servo_output_raw->servo14_raw, servo_output_raw->servo15_raw, servo_output_raw->servo16_raw); -} - -/** - * @brief Send a servo_output_raw message - * @param chan MAVLink channel to send the message - * - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @param port Servo output port (set of 8 outputs = 1 port). Flight stacks running on Pixhawk should use: 0 = MAIN, 1 = AUX. - * @param servo1_raw [us] Servo output 1 value - * @param servo2_raw [us] Servo output 2 value - * @param servo3_raw [us] Servo output 3 value - * @param servo4_raw [us] Servo output 4 value - * @param servo5_raw [us] Servo output 5 value - * @param servo6_raw [us] Servo output 6 value - * @param servo7_raw [us] Servo output 7 value - * @param servo8_raw [us] Servo output 8 value - * @param servo9_raw [us] Servo output 9 value - * @param servo10_raw [us] Servo output 10 value - * @param servo11_raw [us] Servo output 11 value - * @param servo12_raw [us] Servo output 12 value - * @param servo13_raw [us] Servo output 13 value - * @param servo14_raw [us] Servo output 14 value - * @param servo15_raw [us] Servo output 15 value - * @param servo16_raw [us] Servo output 16 value - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_servo_output_raw_send(mavlink_channel_t chan, uint32_t time_usec, uint8_t port, uint16_t servo1_raw, uint16_t servo2_raw, uint16_t servo3_raw, uint16_t servo4_raw, uint16_t servo5_raw, uint16_t servo6_raw, uint16_t servo7_raw, uint16_t servo8_raw, uint16_t servo9_raw, uint16_t servo10_raw, uint16_t servo11_raw, uint16_t servo12_raw, uint16_t servo13_raw, uint16_t servo14_raw, uint16_t servo15_raw, uint16_t servo16_raw) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN]; - _mav_put_uint32_t(buf, 0, time_usec); - _mav_put_uint16_t(buf, 4, servo1_raw); - _mav_put_uint16_t(buf, 6, servo2_raw); - _mav_put_uint16_t(buf, 8, servo3_raw); - _mav_put_uint16_t(buf, 10, servo4_raw); - _mav_put_uint16_t(buf, 12, servo5_raw); - _mav_put_uint16_t(buf, 14, servo6_raw); - _mav_put_uint16_t(buf, 16, servo7_raw); - _mav_put_uint16_t(buf, 18, servo8_raw); - _mav_put_uint8_t(buf, 20, port); - _mav_put_uint16_t(buf, 21, servo9_raw); - _mav_put_uint16_t(buf, 23, servo10_raw); - _mav_put_uint16_t(buf, 25, servo11_raw); - _mav_put_uint16_t(buf, 27, servo12_raw); - _mav_put_uint16_t(buf, 29, servo13_raw); - _mav_put_uint16_t(buf, 31, servo14_raw); - _mav_put_uint16_t(buf, 33, servo15_raw); - _mav_put_uint16_t(buf, 35, servo16_raw); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW, buf, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_MIN_LEN, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_CRC); -#else - mavlink_servo_output_raw_t packet; - packet.time_usec = time_usec; - packet.servo1_raw = servo1_raw; - packet.servo2_raw = servo2_raw; - packet.servo3_raw = servo3_raw; - packet.servo4_raw = servo4_raw; - packet.servo5_raw = servo5_raw; - packet.servo6_raw = servo6_raw; - packet.servo7_raw = servo7_raw; - packet.servo8_raw = servo8_raw; - packet.port = port; - packet.servo9_raw = servo9_raw; - packet.servo10_raw = servo10_raw; - packet.servo11_raw = servo11_raw; - packet.servo12_raw = servo12_raw; - packet.servo13_raw = servo13_raw; - packet.servo14_raw = servo14_raw; - packet.servo15_raw = servo15_raw; - packet.servo16_raw = servo16_raw; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW, (const char *)&packet, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_MIN_LEN, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_CRC); -#endif -} - -/** - * @brief Send a servo_output_raw message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_servo_output_raw_send_struct(mavlink_channel_t chan, const mavlink_servo_output_raw_t* servo_output_raw) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_servo_output_raw_send(chan, servo_output_raw->time_usec, servo_output_raw->port, servo_output_raw->servo1_raw, servo_output_raw->servo2_raw, servo_output_raw->servo3_raw, servo_output_raw->servo4_raw, servo_output_raw->servo5_raw, servo_output_raw->servo6_raw, servo_output_raw->servo7_raw, servo_output_raw->servo8_raw, servo_output_raw->servo9_raw, servo_output_raw->servo10_raw, servo_output_raw->servo11_raw, servo_output_raw->servo12_raw, servo_output_raw->servo13_raw, servo_output_raw->servo14_raw, servo_output_raw->servo15_raw, servo_output_raw->servo16_raw); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW, (const char *)servo_output_raw, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_MIN_LEN, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_CRC); -#endif -} - -#if MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_servo_output_raw_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_usec, uint8_t port, uint16_t servo1_raw, uint16_t servo2_raw, uint16_t servo3_raw, uint16_t servo4_raw, uint16_t servo5_raw, uint16_t servo6_raw, uint16_t servo7_raw, uint16_t servo8_raw, uint16_t servo9_raw, uint16_t servo10_raw, uint16_t servo11_raw, uint16_t servo12_raw, uint16_t servo13_raw, uint16_t servo14_raw, uint16_t servo15_raw, uint16_t servo16_raw) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, time_usec); - _mav_put_uint16_t(buf, 4, servo1_raw); - _mav_put_uint16_t(buf, 6, servo2_raw); - _mav_put_uint16_t(buf, 8, servo3_raw); - _mav_put_uint16_t(buf, 10, servo4_raw); - _mav_put_uint16_t(buf, 12, servo5_raw); - _mav_put_uint16_t(buf, 14, servo6_raw); - _mav_put_uint16_t(buf, 16, servo7_raw); - _mav_put_uint16_t(buf, 18, servo8_raw); - _mav_put_uint8_t(buf, 20, port); - _mav_put_uint16_t(buf, 21, servo9_raw); - _mav_put_uint16_t(buf, 23, servo10_raw); - _mav_put_uint16_t(buf, 25, servo11_raw); - _mav_put_uint16_t(buf, 27, servo12_raw); - _mav_put_uint16_t(buf, 29, servo13_raw); - _mav_put_uint16_t(buf, 31, servo14_raw); - _mav_put_uint16_t(buf, 33, servo15_raw); - _mav_put_uint16_t(buf, 35, servo16_raw); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW, buf, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_MIN_LEN, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_CRC); -#else - mavlink_servo_output_raw_t *packet = (mavlink_servo_output_raw_t *)msgbuf; - packet->time_usec = time_usec; - packet->servo1_raw = servo1_raw; - packet->servo2_raw = servo2_raw; - packet->servo3_raw = servo3_raw; - packet->servo4_raw = servo4_raw; - packet->servo5_raw = servo5_raw; - packet->servo6_raw = servo6_raw; - packet->servo7_raw = servo7_raw; - packet->servo8_raw = servo8_raw; - packet->port = port; - packet->servo9_raw = servo9_raw; - packet->servo10_raw = servo10_raw; - packet->servo11_raw = servo11_raw; - packet->servo12_raw = servo12_raw; - packet->servo13_raw = servo13_raw; - packet->servo14_raw = servo14_raw; - packet->servo15_raw = servo15_raw; - packet->servo16_raw = servo16_raw; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW, (const char *)packet, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_MIN_LEN, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_CRC); -#endif -} -#endif - -#endif - -// MESSAGE SERVO_OUTPUT_RAW UNPACKING - - -/** - * @brief Get field time_usec from servo_output_raw message - * - * @return [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - */ -static inline uint32_t mavlink_msg_servo_output_raw_get_time_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field port from servo_output_raw message - * - * @return Servo output port (set of 8 outputs = 1 port). Flight stacks running on Pixhawk should use: 0 = MAIN, 1 = AUX. - */ -static inline uint8_t mavlink_msg_servo_output_raw_get_port(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 20); -} - -/** - * @brief Get field servo1_raw from servo_output_raw message - * - * @return [us] Servo output 1 value - */ -static inline uint16_t mavlink_msg_servo_output_raw_get_servo1_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 4); -} - -/** - * @brief Get field servo2_raw from servo_output_raw message - * - * @return [us] Servo output 2 value - */ -static inline uint16_t mavlink_msg_servo_output_raw_get_servo2_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 6); -} - -/** - * @brief Get field servo3_raw from servo_output_raw message - * - * @return [us] Servo output 3 value - */ -static inline uint16_t mavlink_msg_servo_output_raw_get_servo3_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 8); -} - -/** - * @brief Get field servo4_raw from servo_output_raw message - * - * @return [us] Servo output 4 value - */ -static inline uint16_t mavlink_msg_servo_output_raw_get_servo4_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 10); -} - -/** - * @brief Get field servo5_raw from servo_output_raw message - * - * @return [us] Servo output 5 value - */ -static inline uint16_t mavlink_msg_servo_output_raw_get_servo5_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 12); -} - -/** - * @brief Get field servo6_raw from servo_output_raw message - * - * @return [us] Servo output 6 value - */ -static inline uint16_t mavlink_msg_servo_output_raw_get_servo6_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 14); -} - -/** - * @brief Get field servo7_raw from servo_output_raw message - * - * @return [us] Servo output 7 value - */ -static inline uint16_t mavlink_msg_servo_output_raw_get_servo7_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 16); -} - -/** - * @brief Get field servo8_raw from servo_output_raw message - * - * @return [us] Servo output 8 value - */ -static inline uint16_t mavlink_msg_servo_output_raw_get_servo8_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 18); -} - -/** - * @brief Get field servo9_raw from servo_output_raw message - * - * @return [us] Servo output 9 value - */ -static inline uint16_t mavlink_msg_servo_output_raw_get_servo9_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 21); -} - -/** - * @brief Get field servo10_raw from servo_output_raw message - * - * @return [us] Servo output 10 value - */ -static inline uint16_t mavlink_msg_servo_output_raw_get_servo10_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 23); -} - -/** - * @brief Get field servo11_raw from servo_output_raw message - * - * @return [us] Servo output 11 value - */ -static inline uint16_t mavlink_msg_servo_output_raw_get_servo11_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 25); -} - -/** - * @brief Get field servo12_raw from servo_output_raw message - * - * @return [us] Servo output 12 value - */ -static inline uint16_t mavlink_msg_servo_output_raw_get_servo12_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 27); -} - -/** - * @brief Get field servo13_raw from servo_output_raw message - * - * @return [us] Servo output 13 value - */ -static inline uint16_t mavlink_msg_servo_output_raw_get_servo13_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 29); -} - -/** - * @brief Get field servo14_raw from servo_output_raw message - * - * @return [us] Servo output 14 value - */ -static inline uint16_t mavlink_msg_servo_output_raw_get_servo14_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 31); -} - -/** - * @brief Get field servo15_raw from servo_output_raw message - * - * @return [us] Servo output 15 value - */ -static inline uint16_t mavlink_msg_servo_output_raw_get_servo15_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 33); -} - -/** - * @brief Get field servo16_raw from servo_output_raw message - * - * @return [us] Servo output 16 value - */ -static inline uint16_t mavlink_msg_servo_output_raw_get_servo16_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 35); -} - -/** - * @brief Decode a servo_output_raw message into a struct - * - * @param msg The message to decode - * @param servo_output_raw C-struct to decode the message contents into - */ -static inline void mavlink_msg_servo_output_raw_decode(const mavlink_message_t* msg, mavlink_servo_output_raw_t* servo_output_raw) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - servo_output_raw->time_usec = mavlink_msg_servo_output_raw_get_time_usec(msg); - servo_output_raw->servo1_raw = mavlink_msg_servo_output_raw_get_servo1_raw(msg); - servo_output_raw->servo2_raw = mavlink_msg_servo_output_raw_get_servo2_raw(msg); - servo_output_raw->servo3_raw = mavlink_msg_servo_output_raw_get_servo3_raw(msg); - servo_output_raw->servo4_raw = mavlink_msg_servo_output_raw_get_servo4_raw(msg); - servo_output_raw->servo5_raw = mavlink_msg_servo_output_raw_get_servo5_raw(msg); - servo_output_raw->servo6_raw = mavlink_msg_servo_output_raw_get_servo6_raw(msg); - servo_output_raw->servo7_raw = mavlink_msg_servo_output_raw_get_servo7_raw(msg); - servo_output_raw->servo8_raw = mavlink_msg_servo_output_raw_get_servo8_raw(msg); - servo_output_raw->port = mavlink_msg_servo_output_raw_get_port(msg); - servo_output_raw->servo9_raw = mavlink_msg_servo_output_raw_get_servo9_raw(msg); - servo_output_raw->servo10_raw = mavlink_msg_servo_output_raw_get_servo10_raw(msg); - servo_output_raw->servo11_raw = mavlink_msg_servo_output_raw_get_servo11_raw(msg); - servo_output_raw->servo12_raw = mavlink_msg_servo_output_raw_get_servo12_raw(msg); - servo_output_raw->servo13_raw = mavlink_msg_servo_output_raw_get_servo13_raw(msg); - servo_output_raw->servo14_raw = mavlink_msg_servo_output_raw_get_servo14_raw(msg); - servo_output_raw->servo15_raw = mavlink_msg_servo_output_raw_get_servo15_raw(msg); - servo_output_raw->servo16_raw = mavlink_msg_servo_output_raw_get_servo16_raw(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN? msg->len : MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN; - memset(servo_output_raw, 0, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN); - memcpy(servo_output_raw, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_set_actuator_control_target.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_set_actuator_control_target.h deleted file mode 100644 index b9ea8fcb..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_set_actuator_control_target.h +++ /dev/null @@ -1,305 +0,0 @@ -#pragma once -// MESSAGE SET_ACTUATOR_CONTROL_TARGET PACKING - -#define MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET 139 - - -typedef struct __mavlink_set_actuator_control_target_t { - uint64_t time_usec; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/ - float controls[8]; /*< Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs.*/ - uint8_t group_mlx; /*< Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances.*/ - uint8_t target_system; /*< System ID*/ - uint8_t target_component; /*< Component ID*/ -} mavlink_set_actuator_control_target_t; - -#define MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_LEN 43 -#define MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_MIN_LEN 43 -#define MAVLINK_MSG_ID_139_LEN 43 -#define MAVLINK_MSG_ID_139_MIN_LEN 43 - -#define MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_CRC 168 -#define MAVLINK_MSG_ID_139_CRC 168 - -#define MAVLINK_MSG_SET_ACTUATOR_CONTROL_TARGET_FIELD_CONTROLS_LEN 8 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_SET_ACTUATOR_CONTROL_TARGET { \ - 139, \ - "SET_ACTUATOR_CONTROL_TARGET", \ - 5, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_set_actuator_control_target_t, time_usec) }, \ - { "group_mlx", NULL, MAVLINK_TYPE_UINT8_T, 0, 40, offsetof(mavlink_set_actuator_control_target_t, group_mlx) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 41, offsetof(mavlink_set_actuator_control_target_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 42, offsetof(mavlink_set_actuator_control_target_t, target_component) }, \ - { "controls", NULL, MAVLINK_TYPE_FLOAT, 8, 8, offsetof(mavlink_set_actuator_control_target_t, controls) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_SET_ACTUATOR_CONTROL_TARGET { \ - "SET_ACTUATOR_CONTROL_TARGET", \ - 5, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_set_actuator_control_target_t, time_usec) }, \ - { "group_mlx", NULL, MAVLINK_TYPE_UINT8_T, 0, 40, offsetof(mavlink_set_actuator_control_target_t, group_mlx) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 41, offsetof(mavlink_set_actuator_control_target_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 42, offsetof(mavlink_set_actuator_control_target_t, target_component) }, \ - { "controls", NULL, MAVLINK_TYPE_FLOAT, 8, 8, offsetof(mavlink_set_actuator_control_target_t, controls) }, \ - } \ -} -#endif - -/** - * @brief Pack a set_actuator_control_target message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @param group_mlx Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances. - * @param target_system System ID - * @param target_component Component ID - * @param controls Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_set_actuator_control_target_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint64_t time_usec, uint8_t group_mlx, uint8_t target_system, uint8_t target_component, const float *controls) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint8_t(buf, 40, group_mlx); - _mav_put_uint8_t(buf, 41, target_system); - _mav_put_uint8_t(buf, 42, target_component); - _mav_put_float_array(buf, 8, controls, 8); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_LEN); -#else - mavlink_set_actuator_control_target_t packet; - packet.time_usec = time_usec; - packet.group_mlx = group_mlx; - packet.target_system = target_system; - packet.target_component = target_component; - mav_array_memcpy(packet.controls, controls, sizeof(float)*8); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_MIN_LEN, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_LEN, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_CRC); -} - -/** - * @brief Pack a set_actuator_control_target message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @param group_mlx Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances. - * @param target_system System ID - * @param target_component Component ID - * @param controls Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_set_actuator_control_target_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint64_t time_usec,uint8_t group_mlx,uint8_t target_system,uint8_t target_component,const float *controls) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint8_t(buf, 40, group_mlx); - _mav_put_uint8_t(buf, 41, target_system); - _mav_put_uint8_t(buf, 42, target_component); - _mav_put_float_array(buf, 8, controls, 8); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_LEN); -#else - mavlink_set_actuator_control_target_t packet; - packet.time_usec = time_usec; - packet.group_mlx = group_mlx; - packet.target_system = target_system; - packet.target_component = target_component; - mav_array_memcpy(packet.controls, controls, sizeof(float)*8); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_MIN_LEN, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_LEN, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_CRC); -} - -/** - * @brief Encode a set_actuator_control_target struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param set_actuator_control_target C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_set_actuator_control_target_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_actuator_control_target_t* set_actuator_control_target) -{ - return mavlink_msg_set_actuator_control_target_pack(system_id, component_id, msg, set_actuator_control_target->time_usec, set_actuator_control_target->group_mlx, set_actuator_control_target->target_system, set_actuator_control_target->target_component, set_actuator_control_target->controls); -} - -/** - * @brief Encode a set_actuator_control_target struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param set_actuator_control_target C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_set_actuator_control_target_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_set_actuator_control_target_t* set_actuator_control_target) -{ - return mavlink_msg_set_actuator_control_target_pack_chan(system_id, component_id, chan, msg, set_actuator_control_target->time_usec, set_actuator_control_target->group_mlx, set_actuator_control_target->target_system, set_actuator_control_target->target_component, set_actuator_control_target->controls); -} - -/** - * @brief Send a set_actuator_control_target message - * @param chan MAVLink channel to send the message - * - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @param group_mlx Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances. - * @param target_system System ID - * @param target_component Component ID - * @param controls Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_set_actuator_control_target_send(mavlink_channel_t chan, uint64_t time_usec, uint8_t group_mlx, uint8_t target_system, uint8_t target_component, const float *controls) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint8_t(buf, 40, group_mlx); - _mav_put_uint8_t(buf, 41, target_system); - _mav_put_uint8_t(buf, 42, target_component); - _mav_put_float_array(buf, 8, controls, 8); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET, buf, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_MIN_LEN, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_LEN, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_CRC); -#else - mavlink_set_actuator_control_target_t packet; - packet.time_usec = time_usec; - packet.group_mlx = group_mlx; - packet.target_system = target_system; - packet.target_component = target_component; - mav_array_memcpy(packet.controls, controls, sizeof(float)*8); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET, (const char *)&packet, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_MIN_LEN, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_LEN, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_CRC); -#endif -} - -/** - * @brief Send a set_actuator_control_target message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_set_actuator_control_target_send_struct(mavlink_channel_t chan, const mavlink_set_actuator_control_target_t* set_actuator_control_target) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_set_actuator_control_target_send(chan, set_actuator_control_target->time_usec, set_actuator_control_target->group_mlx, set_actuator_control_target->target_system, set_actuator_control_target->target_component, set_actuator_control_target->controls); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET, (const char *)set_actuator_control_target, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_MIN_LEN, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_LEN, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_CRC); -#endif -} - -#if MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_set_actuator_control_target_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, uint8_t group_mlx, uint8_t target_system, uint8_t target_component, const float *controls) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint8_t(buf, 40, group_mlx); - _mav_put_uint8_t(buf, 41, target_system); - _mav_put_uint8_t(buf, 42, target_component); - _mav_put_float_array(buf, 8, controls, 8); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET, buf, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_MIN_LEN, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_LEN, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_CRC); -#else - mavlink_set_actuator_control_target_t *packet = (mavlink_set_actuator_control_target_t *)msgbuf; - packet->time_usec = time_usec; - packet->group_mlx = group_mlx; - packet->target_system = target_system; - packet->target_component = target_component; - mav_array_memcpy(packet->controls, controls, sizeof(float)*8); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET, (const char *)packet, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_MIN_LEN, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_LEN, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_CRC); -#endif -} -#endif - -#endif - -// MESSAGE SET_ACTUATOR_CONTROL_TARGET UNPACKING - - -/** - * @brief Get field time_usec from set_actuator_control_target message - * - * @return [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - */ -static inline uint64_t mavlink_msg_set_actuator_control_target_get_time_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field group_mlx from set_actuator_control_target message - * - * @return Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances. - */ -static inline uint8_t mavlink_msg_set_actuator_control_target_get_group_mlx(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 40); -} - -/** - * @brief Get field target_system from set_actuator_control_target message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_set_actuator_control_target_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 41); -} - -/** - * @brief Get field target_component from set_actuator_control_target message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_set_actuator_control_target_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 42); -} - -/** - * @brief Get field controls from set_actuator_control_target message - * - * @return Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs. - */ -static inline uint16_t mavlink_msg_set_actuator_control_target_get_controls(const mavlink_message_t* msg, float *controls) -{ - return _MAV_RETURN_float_array(msg, controls, 8, 8); -} - -/** - * @brief Decode a set_actuator_control_target message into a struct - * - * @param msg The message to decode - * @param set_actuator_control_target C-struct to decode the message contents into - */ -static inline void mavlink_msg_set_actuator_control_target_decode(const mavlink_message_t* msg, mavlink_set_actuator_control_target_t* set_actuator_control_target) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - set_actuator_control_target->time_usec = mavlink_msg_set_actuator_control_target_get_time_usec(msg); - mavlink_msg_set_actuator_control_target_get_controls(msg, set_actuator_control_target->controls); - set_actuator_control_target->group_mlx = mavlink_msg_set_actuator_control_target_get_group_mlx(msg); - set_actuator_control_target->target_system = mavlink_msg_set_actuator_control_target_get_target_system(msg); - set_actuator_control_target->target_component = mavlink_msg_set_actuator_control_target_get_target_component(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_LEN? msg->len : MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_LEN; - memset(set_actuator_control_target, 0, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_LEN); - memcpy(set_actuator_control_target, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_set_attitude_target.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_set_attitude_target.h deleted file mode 100644 index ddf98679..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_set_attitude_target.h +++ /dev/null @@ -1,431 +0,0 @@ -#pragma once -// MESSAGE SET_ATTITUDE_TARGET PACKING - -#define MAVLINK_MSG_ID_SET_ATTITUDE_TARGET 82 - -MAVPACKED( -typedef struct __mavlink_set_attitude_target_t { - uint32_t time_boot_ms; /*< [ms] Timestamp (time since system boot).*/ - float q[4]; /*< Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0)*/ - float body_roll_rate; /*< [rad/s] Body roll rate*/ - float body_pitch_rate; /*< [rad/s] Body pitch rate*/ - float body_yaw_rate; /*< [rad/s] Body yaw rate*/ - float thrust; /*< Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust)*/ - uint8_t target_system; /*< System ID*/ - uint8_t target_component; /*< Component ID*/ - uint8_t type_mask; /*< Bitmap to indicate which dimensions should be ignored by the vehicle.*/ - float thrust_body[3]; /*< 3D thrust setpoint in the body NED frame, normalized to -1 .. 1*/ -}) mavlink_set_attitude_target_t; - -#define MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN 51 -#define MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_MIN_LEN 39 -#define MAVLINK_MSG_ID_82_LEN 51 -#define MAVLINK_MSG_ID_82_MIN_LEN 39 - -#define MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_CRC 49 -#define MAVLINK_MSG_ID_82_CRC 49 - -#define MAVLINK_MSG_SET_ATTITUDE_TARGET_FIELD_Q_LEN 4 -#define MAVLINK_MSG_SET_ATTITUDE_TARGET_FIELD_THRUST_BODY_LEN 3 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_SET_ATTITUDE_TARGET { \ - 82, \ - "SET_ATTITUDE_TARGET", \ - 10, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_set_attitude_target_t, time_boot_ms) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_set_attitude_target_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 37, offsetof(mavlink_set_attitude_target_t, target_component) }, \ - { "type_mask", NULL, MAVLINK_TYPE_UINT8_T, 0, 38, offsetof(mavlink_set_attitude_target_t, type_mask) }, \ - { "q", NULL, MAVLINK_TYPE_FLOAT, 4, 4, offsetof(mavlink_set_attitude_target_t, q) }, \ - { "body_roll_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_set_attitude_target_t, body_roll_rate) }, \ - { "body_pitch_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_set_attitude_target_t, body_pitch_rate) }, \ - { "body_yaw_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_set_attitude_target_t, body_yaw_rate) }, \ - { "thrust", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_set_attitude_target_t, thrust) }, \ - { "thrust_body", NULL, MAVLINK_TYPE_FLOAT, 3, 39, offsetof(mavlink_set_attitude_target_t, thrust_body) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_SET_ATTITUDE_TARGET { \ - "SET_ATTITUDE_TARGET", \ - 10, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_set_attitude_target_t, time_boot_ms) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_set_attitude_target_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 37, offsetof(mavlink_set_attitude_target_t, target_component) }, \ - { "type_mask", NULL, MAVLINK_TYPE_UINT8_T, 0, 38, offsetof(mavlink_set_attitude_target_t, type_mask) }, \ - { "q", NULL, MAVLINK_TYPE_FLOAT, 4, 4, offsetof(mavlink_set_attitude_target_t, q) }, \ - { "body_roll_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_set_attitude_target_t, body_roll_rate) }, \ - { "body_pitch_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_set_attitude_target_t, body_pitch_rate) }, \ - { "body_yaw_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_set_attitude_target_t, body_yaw_rate) }, \ - { "thrust", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_set_attitude_target_t, thrust) }, \ - { "thrust_body", NULL, MAVLINK_TYPE_FLOAT, 3, 39, offsetof(mavlink_set_attitude_target_t, thrust_body) }, \ - } \ -} -#endif - -/** - * @brief Pack a set_attitude_target message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param time_boot_ms [ms] Timestamp (time since system boot). - * @param target_system System ID - * @param target_component Component ID - * @param type_mask Bitmap to indicate which dimensions should be ignored by the vehicle. - * @param q Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) - * @param body_roll_rate [rad/s] Body roll rate - * @param body_pitch_rate [rad/s] Body pitch rate - * @param body_yaw_rate [rad/s] Body yaw rate - * @param thrust Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust) - * @param thrust_body 3D thrust setpoint in the body NED frame, normalized to -1 .. 1 - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_set_attitude_target_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint32_t time_boot_ms, uint8_t target_system, uint8_t target_component, uint8_t type_mask, const float *q, float body_roll_rate, float body_pitch_rate, float body_yaw_rate, float thrust, const float *thrust_body) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 20, body_roll_rate); - _mav_put_float(buf, 24, body_pitch_rate); - _mav_put_float(buf, 28, body_yaw_rate); - _mav_put_float(buf, 32, thrust); - _mav_put_uint8_t(buf, 36, target_system); - _mav_put_uint8_t(buf, 37, target_component); - _mav_put_uint8_t(buf, 38, type_mask); - _mav_put_float_array(buf, 4, q, 4); - _mav_put_float_array(buf, 39, thrust_body, 3); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN); -#else - mavlink_set_attitude_target_t packet; - packet.time_boot_ms = time_boot_ms; - packet.body_roll_rate = body_roll_rate; - packet.body_pitch_rate = body_pitch_rate; - packet.body_yaw_rate = body_yaw_rate; - packet.thrust = thrust; - packet.target_system = target_system; - packet.target_component = target_component; - packet.type_mask = type_mask; - mav_array_memcpy(packet.q, q, sizeof(float)*4); - mav_array_memcpy(packet.thrust_body, thrust_body, sizeof(float)*3); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SET_ATTITUDE_TARGET; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_MIN_LEN, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_CRC); -} - -/** - * @brief Pack a set_attitude_target message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_boot_ms [ms] Timestamp (time since system boot). - * @param target_system System ID - * @param target_component Component ID - * @param type_mask Bitmap to indicate which dimensions should be ignored by the vehicle. - * @param q Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) - * @param body_roll_rate [rad/s] Body roll rate - * @param body_pitch_rate [rad/s] Body pitch rate - * @param body_yaw_rate [rad/s] Body yaw rate - * @param thrust Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust) - * @param thrust_body 3D thrust setpoint in the body NED frame, normalized to -1 .. 1 - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_set_attitude_target_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint32_t time_boot_ms,uint8_t target_system,uint8_t target_component,uint8_t type_mask,const float *q,float body_roll_rate,float body_pitch_rate,float body_yaw_rate,float thrust,const float *thrust_body) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 20, body_roll_rate); - _mav_put_float(buf, 24, body_pitch_rate); - _mav_put_float(buf, 28, body_yaw_rate); - _mav_put_float(buf, 32, thrust); - _mav_put_uint8_t(buf, 36, target_system); - _mav_put_uint8_t(buf, 37, target_component); - _mav_put_uint8_t(buf, 38, type_mask); - _mav_put_float_array(buf, 4, q, 4); - _mav_put_float_array(buf, 39, thrust_body, 3); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN); -#else - mavlink_set_attitude_target_t packet; - packet.time_boot_ms = time_boot_ms; - packet.body_roll_rate = body_roll_rate; - packet.body_pitch_rate = body_pitch_rate; - packet.body_yaw_rate = body_yaw_rate; - packet.thrust = thrust; - packet.target_system = target_system; - packet.target_component = target_component; - packet.type_mask = type_mask; - mav_array_memcpy(packet.q, q, sizeof(float)*4); - mav_array_memcpy(packet.thrust_body, thrust_body, sizeof(float)*3); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SET_ATTITUDE_TARGET; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_MIN_LEN, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_CRC); -} - -/** - * @brief Encode a set_attitude_target struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param set_attitude_target C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_set_attitude_target_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_attitude_target_t* set_attitude_target) -{ - return mavlink_msg_set_attitude_target_pack(system_id, component_id, msg, set_attitude_target->time_boot_ms, set_attitude_target->target_system, set_attitude_target->target_component, set_attitude_target->type_mask, set_attitude_target->q, set_attitude_target->body_roll_rate, set_attitude_target->body_pitch_rate, set_attitude_target->body_yaw_rate, set_attitude_target->thrust, set_attitude_target->thrust_body); -} - -/** - * @brief Encode a set_attitude_target struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param set_attitude_target C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_set_attitude_target_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_set_attitude_target_t* set_attitude_target) -{ - return mavlink_msg_set_attitude_target_pack_chan(system_id, component_id, chan, msg, set_attitude_target->time_boot_ms, set_attitude_target->target_system, set_attitude_target->target_component, set_attitude_target->type_mask, set_attitude_target->q, set_attitude_target->body_roll_rate, set_attitude_target->body_pitch_rate, set_attitude_target->body_yaw_rate, set_attitude_target->thrust, set_attitude_target->thrust_body); -} - -/** - * @brief Send a set_attitude_target message - * @param chan MAVLink channel to send the message - * - * @param time_boot_ms [ms] Timestamp (time since system boot). - * @param target_system System ID - * @param target_component Component ID - * @param type_mask Bitmap to indicate which dimensions should be ignored by the vehicle. - * @param q Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) - * @param body_roll_rate [rad/s] Body roll rate - * @param body_pitch_rate [rad/s] Body pitch rate - * @param body_yaw_rate [rad/s] Body yaw rate - * @param thrust Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust) - * @param thrust_body 3D thrust setpoint in the body NED frame, normalized to -1 .. 1 - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_set_attitude_target_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t target_system, uint8_t target_component, uint8_t type_mask, const float *q, float body_roll_rate, float body_pitch_rate, float body_yaw_rate, float thrust, const float *thrust_body) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 20, body_roll_rate); - _mav_put_float(buf, 24, body_pitch_rate); - _mav_put_float(buf, 28, body_yaw_rate); - _mav_put_float(buf, 32, thrust); - _mav_put_uint8_t(buf, 36, target_system); - _mav_put_uint8_t(buf, 37, target_component); - _mav_put_uint8_t(buf, 38, type_mask); - _mav_put_float_array(buf, 4, q, 4); - _mav_put_float_array(buf, 39, thrust_body, 3); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET, buf, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_MIN_LEN, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_CRC); -#else - mavlink_set_attitude_target_t packet; - packet.time_boot_ms = time_boot_ms; - packet.body_roll_rate = body_roll_rate; - packet.body_pitch_rate = body_pitch_rate; - packet.body_yaw_rate = body_yaw_rate; - packet.thrust = thrust; - packet.target_system = target_system; - packet.target_component = target_component; - packet.type_mask = type_mask; - mav_array_memcpy(packet.q, q, sizeof(float)*4); - mav_array_memcpy(packet.thrust_body, thrust_body, sizeof(float)*3); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET, (const char *)&packet, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_MIN_LEN, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_CRC); -#endif -} - -/** - * @brief Send a set_attitude_target message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_set_attitude_target_send_struct(mavlink_channel_t chan, const mavlink_set_attitude_target_t* set_attitude_target) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_set_attitude_target_send(chan, set_attitude_target->time_boot_ms, set_attitude_target->target_system, set_attitude_target->target_component, set_attitude_target->type_mask, set_attitude_target->q, set_attitude_target->body_roll_rate, set_attitude_target->body_pitch_rate, set_attitude_target->body_yaw_rate, set_attitude_target->thrust, set_attitude_target->thrust_body); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET, (const char *)set_attitude_target, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_MIN_LEN, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_CRC); -#endif -} - -#if MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_set_attitude_target_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t target_system, uint8_t target_component, uint8_t type_mask, const float *q, float body_roll_rate, float body_pitch_rate, float body_yaw_rate, float thrust, const float *thrust_body) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 20, body_roll_rate); - _mav_put_float(buf, 24, body_pitch_rate); - _mav_put_float(buf, 28, body_yaw_rate); - _mav_put_float(buf, 32, thrust); - _mav_put_uint8_t(buf, 36, target_system); - _mav_put_uint8_t(buf, 37, target_component); - _mav_put_uint8_t(buf, 38, type_mask); - _mav_put_float_array(buf, 4, q, 4); - _mav_put_float_array(buf, 39, thrust_body, 3); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET, buf, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_MIN_LEN, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_CRC); -#else - mavlink_set_attitude_target_t *packet = (mavlink_set_attitude_target_t *)msgbuf; - packet->time_boot_ms = time_boot_ms; - packet->body_roll_rate = body_roll_rate; - packet->body_pitch_rate = body_pitch_rate; - packet->body_yaw_rate = body_yaw_rate; - packet->thrust = thrust; - packet->target_system = target_system; - packet->target_component = target_component; - packet->type_mask = type_mask; - mav_array_memcpy(packet->q, q, sizeof(float)*4); - mav_array_memcpy(packet->thrust_body, thrust_body, sizeof(float)*3); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET, (const char *)packet, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_MIN_LEN, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_CRC); -#endif -} -#endif - -#endif - -// MESSAGE SET_ATTITUDE_TARGET UNPACKING - - -/** - * @brief Get field time_boot_ms from set_attitude_target message - * - * @return [ms] Timestamp (time since system boot). - */ -static inline uint32_t mavlink_msg_set_attitude_target_get_time_boot_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field target_system from set_attitude_target message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_set_attitude_target_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 36); -} - -/** - * @brief Get field target_component from set_attitude_target message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_set_attitude_target_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 37); -} - -/** - * @brief Get field type_mask from set_attitude_target message - * - * @return Bitmap to indicate which dimensions should be ignored by the vehicle. - */ -static inline uint8_t mavlink_msg_set_attitude_target_get_type_mask(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 38); -} - -/** - * @brief Get field q from set_attitude_target message - * - * @return Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) - */ -static inline uint16_t mavlink_msg_set_attitude_target_get_q(const mavlink_message_t* msg, float *q) -{ - return _MAV_RETURN_float_array(msg, q, 4, 4); -} - -/** - * @brief Get field body_roll_rate from set_attitude_target message - * - * @return [rad/s] Body roll rate - */ -static inline float mavlink_msg_set_attitude_target_get_body_roll_rate(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Get field body_pitch_rate from set_attitude_target message - * - * @return [rad/s] Body pitch rate - */ -static inline float mavlink_msg_set_attitude_target_get_body_pitch_rate(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Get field body_yaw_rate from set_attitude_target message - * - * @return [rad/s] Body yaw rate - */ -static inline float mavlink_msg_set_attitude_target_get_body_yaw_rate(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 28); -} - -/** - * @brief Get field thrust from set_attitude_target message - * - * @return Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust) - */ -static inline float mavlink_msg_set_attitude_target_get_thrust(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 32); -} - -/** - * @brief Get field thrust_body from set_attitude_target message - * - * @return 3D thrust setpoint in the body NED frame, normalized to -1 .. 1 - */ -static inline uint16_t mavlink_msg_set_attitude_target_get_thrust_body(const mavlink_message_t* msg, float *thrust_body) -{ - return _MAV_RETURN_float_array(msg, thrust_body, 3, 39); -} - -/** - * @brief Decode a set_attitude_target message into a struct - * - * @param msg The message to decode - * @param set_attitude_target C-struct to decode the message contents into - */ -static inline void mavlink_msg_set_attitude_target_decode(const mavlink_message_t* msg, mavlink_set_attitude_target_t* set_attitude_target) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - set_attitude_target->time_boot_ms = mavlink_msg_set_attitude_target_get_time_boot_ms(msg); - mavlink_msg_set_attitude_target_get_q(msg, set_attitude_target->q); - set_attitude_target->body_roll_rate = mavlink_msg_set_attitude_target_get_body_roll_rate(msg); - set_attitude_target->body_pitch_rate = mavlink_msg_set_attitude_target_get_body_pitch_rate(msg); - set_attitude_target->body_yaw_rate = mavlink_msg_set_attitude_target_get_body_yaw_rate(msg); - set_attitude_target->thrust = mavlink_msg_set_attitude_target_get_thrust(msg); - set_attitude_target->target_system = mavlink_msg_set_attitude_target_get_target_system(msg); - set_attitude_target->target_component = mavlink_msg_set_attitude_target_get_target_component(msg); - set_attitude_target->type_mask = mavlink_msg_set_attitude_target_get_type_mask(msg); - mavlink_msg_set_attitude_target_get_thrust_body(msg, set_attitude_target->thrust_body); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN? msg->len : MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN; - memset(set_attitude_target, 0, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN); - memcpy(set_attitude_target, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_set_gps_global_origin.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_set_gps_global_origin.h deleted file mode 100644 index 88ab89b8..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_set_gps_global_origin.h +++ /dev/null @@ -1,313 +0,0 @@ -#pragma once -// MESSAGE SET_GPS_GLOBAL_ORIGIN PACKING - -#define MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN 48 - -MAVPACKED( -typedef struct __mavlink_set_gps_global_origin_t { - int32_t latitude; /*< [degE7] Latitude (WGS84)*/ - int32_t longitude; /*< [degE7] Longitude (WGS84)*/ - int32_t altitude; /*< [mm] Altitude (MSL). Positive for up.*/ - uint8_t target_system; /*< System ID*/ - uint64_t time_usec; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/ -}) mavlink_set_gps_global_origin_t; - -#define MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN 21 -#define MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_MIN_LEN 13 -#define MAVLINK_MSG_ID_48_LEN 21 -#define MAVLINK_MSG_ID_48_MIN_LEN 13 - -#define MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_CRC 41 -#define MAVLINK_MSG_ID_48_CRC 41 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_SET_GPS_GLOBAL_ORIGIN { \ - 48, \ - "SET_GPS_GLOBAL_ORIGIN", \ - 5, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_set_gps_global_origin_t, target_system) }, \ - { "latitude", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_set_gps_global_origin_t, latitude) }, \ - { "longitude", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_set_gps_global_origin_t, longitude) }, \ - { "altitude", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_set_gps_global_origin_t, altitude) }, \ - { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 13, offsetof(mavlink_set_gps_global_origin_t, time_usec) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_SET_GPS_GLOBAL_ORIGIN { \ - "SET_GPS_GLOBAL_ORIGIN", \ - 5, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_set_gps_global_origin_t, target_system) }, \ - { "latitude", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_set_gps_global_origin_t, latitude) }, \ - { "longitude", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_set_gps_global_origin_t, longitude) }, \ - { "altitude", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_set_gps_global_origin_t, altitude) }, \ - { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 13, offsetof(mavlink_set_gps_global_origin_t, time_usec) }, \ - } \ -} -#endif - -/** - * @brief Pack a set_gps_global_origin message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID - * @param latitude [degE7] Latitude (WGS84) - * @param longitude [degE7] Longitude (WGS84) - * @param altitude [mm] Altitude (MSL). Positive for up. - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_set_gps_global_origin_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, int32_t latitude, int32_t longitude, int32_t altitude, uint64_t time_usec) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN]; - _mav_put_int32_t(buf, 0, latitude); - _mav_put_int32_t(buf, 4, longitude); - _mav_put_int32_t(buf, 8, altitude); - _mav_put_uint8_t(buf, 12, target_system); - _mav_put_uint64_t(buf, 13, time_usec); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN); -#else - mavlink_set_gps_global_origin_t packet; - packet.latitude = latitude; - packet.longitude = longitude; - packet.altitude = altitude; - packet.target_system = target_system; - packet.time_usec = time_usec; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_MIN_LEN, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_CRC); -} - -/** - * @brief Pack a set_gps_global_origin message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param latitude [degE7] Latitude (WGS84) - * @param longitude [degE7] Longitude (WGS84) - * @param altitude [mm] Altitude (MSL). Positive for up. - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_set_gps_global_origin_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,int32_t latitude,int32_t longitude,int32_t altitude,uint64_t time_usec) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN]; - _mav_put_int32_t(buf, 0, latitude); - _mav_put_int32_t(buf, 4, longitude); - _mav_put_int32_t(buf, 8, altitude); - _mav_put_uint8_t(buf, 12, target_system); - _mav_put_uint64_t(buf, 13, time_usec); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN); -#else - mavlink_set_gps_global_origin_t packet; - packet.latitude = latitude; - packet.longitude = longitude; - packet.altitude = altitude; - packet.target_system = target_system; - packet.time_usec = time_usec; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_MIN_LEN, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_CRC); -} - -/** - * @brief Encode a set_gps_global_origin struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param set_gps_global_origin C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_set_gps_global_origin_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_gps_global_origin_t* set_gps_global_origin) -{ - return mavlink_msg_set_gps_global_origin_pack(system_id, component_id, msg, set_gps_global_origin->target_system, set_gps_global_origin->latitude, set_gps_global_origin->longitude, set_gps_global_origin->altitude, set_gps_global_origin->time_usec); -} - -/** - * @brief Encode a set_gps_global_origin struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param set_gps_global_origin C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_set_gps_global_origin_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_set_gps_global_origin_t* set_gps_global_origin) -{ - return mavlink_msg_set_gps_global_origin_pack_chan(system_id, component_id, chan, msg, set_gps_global_origin->target_system, set_gps_global_origin->latitude, set_gps_global_origin->longitude, set_gps_global_origin->altitude, set_gps_global_origin->time_usec); -} - -/** - * @brief Send a set_gps_global_origin message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param latitude [degE7] Latitude (WGS84) - * @param longitude [degE7] Longitude (WGS84) - * @param altitude [mm] Altitude (MSL). Positive for up. - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_set_gps_global_origin_send(mavlink_channel_t chan, uint8_t target_system, int32_t latitude, int32_t longitude, int32_t altitude, uint64_t time_usec) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN]; - _mav_put_int32_t(buf, 0, latitude); - _mav_put_int32_t(buf, 4, longitude); - _mav_put_int32_t(buf, 8, altitude); - _mav_put_uint8_t(buf, 12, target_system); - _mav_put_uint64_t(buf, 13, time_usec); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN, buf, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_MIN_LEN, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_CRC); -#else - mavlink_set_gps_global_origin_t packet; - packet.latitude = latitude; - packet.longitude = longitude; - packet.altitude = altitude; - packet.target_system = target_system; - packet.time_usec = time_usec; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN, (const char *)&packet, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_MIN_LEN, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_CRC); -#endif -} - -/** - * @brief Send a set_gps_global_origin message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_set_gps_global_origin_send_struct(mavlink_channel_t chan, const mavlink_set_gps_global_origin_t* set_gps_global_origin) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_set_gps_global_origin_send(chan, set_gps_global_origin->target_system, set_gps_global_origin->latitude, set_gps_global_origin->longitude, set_gps_global_origin->altitude, set_gps_global_origin->time_usec); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN, (const char *)set_gps_global_origin, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_MIN_LEN, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_CRC); -#endif -} - -#if MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_set_gps_global_origin_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, int32_t latitude, int32_t longitude, int32_t altitude, uint64_t time_usec) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_int32_t(buf, 0, latitude); - _mav_put_int32_t(buf, 4, longitude); - _mav_put_int32_t(buf, 8, altitude); - _mav_put_uint8_t(buf, 12, target_system); - _mav_put_uint64_t(buf, 13, time_usec); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN, buf, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_MIN_LEN, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_CRC); -#else - mavlink_set_gps_global_origin_t *packet = (mavlink_set_gps_global_origin_t *)msgbuf; - packet->latitude = latitude; - packet->longitude = longitude; - packet->altitude = altitude; - packet->target_system = target_system; - packet->time_usec = time_usec; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN, (const char *)packet, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_MIN_LEN, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_CRC); -#endif -} -#endif - -#endif - -// MESSAGE SET_GPS_GLOBAL_ORIGIN UNPACKING - - -/** - * @brief Get field target_system from set_gps_global_origin message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_set_gps_global_origin_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 12); -} - -/** - * @brief Get field latitude from set_gps_global_origin message - * - * @return [degE7] Latitude (WGS84) - */ -static inline int32_t mavlink_msg_set_gps_global_origin_get_latitude(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 0); -} - -/** - * @brief Get field longitude from set_gps_global_origin message - * - * @return [degE7] Longitude (WGS84) - */ -static inline int32_t mavlink_msg_set_gps_global_origin_get_longitude(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 4); -} - -/** - * @brief Get field altitude from set_gps_global_origin message - * - * @return [mm] Altitude (MSL). Positive for up. - */ -static inline int32_t mavlink_msg_set_gps_global_origin_get_altitude(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 8); -} - -/** - * @brief Get field time_usec from set_gps_global_origin message - * - * @return [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - */ -static inline uint64_t mavlink_msg_set_gps_global_origin_get_time_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 13); -} - -/** - * @brief Decode a set_gps_global_origin message into a struct - * - * @param msg The message to decode - * @param set_gps_global_origin C-struct to decode the message contents into - */ -static inline void mavlink_msg_set_gps_global_origin_decode(const mavlink_message_t* msg, mavlink_set_gps_global_origin_t* set_gps_global_origin) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - set_gps_global_origin->latitude = mavlink_msg_set_gps_global_origin_get_latitude(msg); - set_gps_global_origin->longitude = mavlink_msg_set_gps_global_origin_get_longitude(msg); - set_gps_global_origin->altitude = mavlink_msg_set_gps_global_origin_get_altitude(msg); - set_gps_global_origin->target_system = mavlink_msg_set_gps_global_origin_get_target_system(msg); - set_gps_global_origin->time_usec = mavlink_msg_set_gps_global_origin_get_time_usec(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN? msg->len : MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN; - memset(set_gps_global_origin, 0, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN); - memcpy(set_gps_global_origin, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_set_home_position.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_set_home_position.h deleted file mode 100644 index 0bb34d7c..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_set_home_position.h +++ /dev/null @@ -1,480 +0,0 @@ -#pragma once -// MESSAGE SET_HOME_POSITION PACKING - -#define MAVLINK_MSG_ID_SET_HOME_POSITION 243 - -MAVPACKED( -typedef struct __mavlink_set_home_position_t { - int32_t latitude; /*< [degE7] Latitude (WGS84)*/ - int32_t longitude; /*< [degE7] Longitude (WGS84)*/ - int32_t altitude; /*< [mm] Altitude (MSL). Positive for up.*/ - float x; /*< [m] Local X position of this position in the local coordinate frame (NED)*/ - float y; /*< [m] Local Y position of this position in the local coordinate frame (NED)*/ - float z; /*< [m] Local Z position of this position in the local coordinate frame (NED: positive "down")*/ - float q[4]; /*< World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground*/ - float approach_x; /*< [m] Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.*/ - float approach_y; /*< [m] Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.*/ - float approach_z; /*< [m] Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.*/ - uint8_t target_system; /*< System ID.*/ - uint64_t time_usec; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/ -}) mavlink_set_home_position_t; - -#define MAVLINK_MSG_ID_SET_HOME_POSITION_LEN 61 -#define MAVLINK_MSG_ID_SET_HOME_POSITION_MIN_LEN 53 -#define MAVLINK_MSG_ID_243_LEN 61 -#define MAVLINK_MSG_ID_243_MIN_LEN 53 - -#define MAVLINK_MSG_ID_SET_HOME_POSITION_CRC 85 -#define MAVLINK_MSG_ID_243_CRC 85 - -#define MAVLINK_MSG_SET_HOME_POSITION_FIELD_Q_LEN 4 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_SET_HOME_POSITION { \ - 243, \ - "SET_HOME_POSITION", \ - 12, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 52, offsetof(mavlink_set_home_position_t, target_system) }, \ - { "latitude", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_set_home_position_t, latitude) }, \ - { "longitude", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_set_home_position_t, longitude) }, \ - { "altitude", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_set_home_position_t, altitude) }, \ - { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_set_home_position_t, x) }, \ - { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_set_home_position_t, y) }, \ - { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_set_home_position_t, z) }, \ - { "q", NULL, MAVLINK_TYPE_FLOAT, 4, 24, offsetof(mavlink_set_home_position_t, q) }, \ - { "approach_x", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_set_home_position_t, approach_x) }, \ - { "approach_y", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_set_home_position_t, approach_y) }, \ - { "approach_z", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_set_home_position_t, approach_z) }, \ - { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 53, offsetof(mavlink_set_home_position_t, time_usec) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_SET_HOME_POSITION { \ - "SET_HOME_POSITION", \ - 12, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 52, offsetof(mavlink_set_home_position_t, target_system) }, \ - { "latitude", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_set_home_position_t, latitude) }, \ - { "longitude", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_set_home_position_t, longitude) }, \ - { "altitude", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_set_home_position_t, altitude) }, \ - { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_set_home_position_t, x) }, \ - { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_set_home_position_t, y) }, \ - { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_set_home_position_t, z) }, \ - { "q", NULL, MAVLINK_TYPE_FLOAT, 4, 24, offsetof(mavlink_set_home_position_t, q) }, \ - { "approach_x", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_set_home_position_t, approach_x) }, \ - { "approach_y", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_set_home_position_t, approach_y) }, \ - { "approach_z", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_set_home_position_t, approach_z) }, \ - { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 53, offsetof(mavlink_set_home_position_t, time_usec) }, \ - } \ -} -#endif - -/** - * @brief Pack a set_home_position message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID. - * @param latitude [degE7] Latitude (WGS84) - * @param longitude [degE7] Longitude (WGS84) - * @param altitude [mm] Altitude (MSL). Positive for up. - * @param x [m] Local X position of this position in the local coordinate frame (NED) - * @param y [m] Local Y position of this position in the local coordinate frame (NED) - * @param z [m] Local Z position of this position in the local coordinate frame (NED: positive "down") - * @param q World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground - * @param approach_x [m] Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. - * @param approach_y [m] Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. - * @param approach_z [m] Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_set_home_position_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, int32_t latitude, int32_t longitude, int32_t altitude, float x, float y, float z, const float *q, float approach_x, float approach_y, float approach_z, uint64_t time_usec) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SET_HOME_POSITION_LEN]; - _mav_put_int32_t(buf, 0, latitude); - _mav_put_int32_t(buf, 4, longitude); - _mav_put_int32_t(buf, 8, altitude); - _mav_put_float(buf, 12, x); - _mav_put_float(buf, 16, y); - _mav_put_float(buf, 20, z); - _mav_put_float(buf, 40, approach_x); - _mav_put_float(buf, 44, approach_y); - _mav_put_float(buf, 48, approach_z); - _mav_put_uint8_t(buf, 52, target_system); - _mav_put_uint64_t(buf, 53, time_usec); - _mav_put_float_array(buf, 24, q, 4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_HOME_POSITION_LEN); -#else - mavlink_set_home_position_t packet; - packet.latitude = latitude; - packet.longitude = longitude; - packet.altitude = altitude; - packet.x = x; - packet.y = y; - packet.z = z; - packet.approach_x = approach_x; - packet.approach_y = approach_y; - packet.approach_z = approach_z; - packet.target_system = target_system; - packet.time_usec = time_usec; - mav_array_memcpy(packet.q, q, sizeof(float)*4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_HOME_POSITION_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SET_HOME_POSITION; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_HOME_POSITION_MIN_LEN, MAVLINK_MSG_ID_SET_HOME_POSITION_LEN, MAVLINK_MSG_ID_SET_HOME_POSITION_CRC); -} - -/** - * @brief Pack a set_home_position message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID. - * @param latitude [degE7] Latitude (WGS84) - * @param longitude [degE7] Longitude (WGS84) - * @param altitude [mm] Altitude (MSL). Positive for up. - * @param x [m] Local X position of this position in the local coordinate frame (NED) - * @param y [m] Local Y position of this position in the local coordinate frame (NED) - * @param z [m] Local Z position of this position in the local coordinate frame (NED: positive "down") - * @param q World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground - * @param approach_x [m] Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. - * @param approach_y [m] Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. - * @param approach_z [m] Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_set_home_position_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,int32_t latitude,int32_t longitude,int32_t altitude,float x,float y,float z,const float *q,float approach_x,float approach_y,float approach_z,uint64_t time_usec) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SET_HOME_POSITION_LEN]; - _mav_put_int32_t(buf, 0, latitude); - _mav_put_int32_t(buf, 4, longitude); - _mav_put_int32_t(buf, 8, altitude); - _mav_put_float(buf, 12, x); - _mav_put_float(buf, 16, y); - _mav_put_float(buf, 20, z); - _mav_put_float(buf, 40, approach_x); - _mav_put_float(buf, 44, approach_y); - _mav_put_float(buf, 48, approach_z); - _mav_put_uint8_t(buf, 52, target_system); - _mav_put_uint64_t(buf, 53, time_usec); - _mav_put_float_array(buf, 24, q, 4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_HOME_POSITION_LEN); -#else - mavlink_set_home_position_t packet; - packet.latitude = latitude; - packet.longitude = longitude; - packet.altitude = altitude; - packet.x = x; - packet.y = y; - packet.z = z; - packet.approach_x = approach_x; - packet.approach_y = approach_y; - packet.approach_z = approach_z; - packet.target_system = target_system; - packet.time_usec = time_usec; - mav_array_memcpy(packet.q, q, sizeof(float)*4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_HOME_POSITION_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SET_HOME_POSITION; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_HOME_POSITION_MIN_LEN, MAVLINK_MSG_ID_SET_HOME_POSITION_LEN, MAVLINK_MSG_ID_SET_HOME_POSITION_CRC); -} - -/** - * @brief Encode a set_home_position struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param set_home_position C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_set_home_position_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_home_position_t* set_home_position) -{ - return mavlink_msg_set_home_position_pack(system_id, component_id, msg, set_home_position->target_system, set_home_position->latitude, set_home_position->longitude, set_home_position->altitude, set_home_position->x, set_home_position->y, set_home_position->z, set_home_position->q, set_home_position->approach_x, set_home_position->approach_y, set_home_position->approach_z, set_home_position->time_usec); -} - -/** - * @brief Encode a set_home_position struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param set_home_position C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_set_home_position_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_set_home_position_t* set_home_position) -{ - return mavlink_msg_set_home_position_pack_chan(system_id, component_id, chan, msg, set_home_position->target_system, set_home_position->latitude, set_home_position->longitude, set_home_position->altitude, set_home_position->x, set_home_position->y, set_home_position->z, set_home_position->q, set_home_position->approach_x, set_home_position->approach_y, set_home_position->approach_z, set_home_position->time_usec); -} - -/** - * @brief Send a set_home_position message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID. - * @param latitude [degE7] Latitude (WGS84) - * @param longitude [degE7] Longitude (WGS84) - * @param altitude [mm] Altitude (MSL). Positive for up. - * @param x [m] Local X position of this position in the local coordinate frame (NED) - * @param y [m] Local Y position of this position in the local coordinate frame (NED) - * @param z [m] Local Z position of this position in the local coordinate frame (NED: positive "down") - * @param q World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground - * @param approach_x [m] Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. - * @param approach_y [m] Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. - * @param approach_z [m] Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_set_home_position_send(mavlink_channel_t chan, uint8_t target_system, int32_t latitude, int32_t longitude, int32_t altitude, float x, float y, float z, const float *q, float approach_x, float approach_y, float approach_z, uint64_t time_usec) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SET_HOME_POSITION_LEN]; - _mav_put_int32_t(buf, 0, latitude); - _mav_put_int32_t(buf, 4, longitude); - _mav_put_int32_t(buf, 8, altitude); - _mav_put_float(buf, 12, x); - _mav_put_float(buf, 16, y); - _mav_put_float(buf, 20, z); - _mav_put_float(buf, 40, approach_x); - _mav_put_float(buf, 44, approach_y); - _mav_put_float(buf, 48, approach_z); - _mav_put_uint8_t(buf, 52, target_system); - _mav_put_uint64_t(buf, 53, time_usec); - _mav_put_float_array(buf, 24, q, 4); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_HOME_POSITION, buf, MAVLINK_MSG_ID_SET_HOME_POSITION_MIN_LEN, MAVLINK_MSG_ID_SET_HOME_POSITION_LEN, MAVLINK_MSG_ID_SET_HOME_POSITION_CRC); -#else - mavlink_set_home_position_t packet; - packet.latitude = latitude; - packet.longitude = longitude; - packet.altitude = altitude; - packet.x = x; - packet.y = y; - packet.z = z; - packet.approach_x = approach_x; - packet.approach_y = approach_y; - packet.approach_z = approach_z; - packet.target_system = target_system; - packet.time_usec = time_usec; - mav_array_memcpy(packet.q, q, sizeof(float)*4); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_HOME_POSITION, (const char *)&packet, MAVLINK_MSG_ID_SET_HOME_POSITION_MIN_LEN, MAVLINK_MSG_ID_SET_HOME_POSITION_LEN, MAVLINK_MSG_ID_SET_HOME_POSITION_CRC); -#endif -} - -/** - * @brief Send a set_home_position message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_set_home_position_send_struct(mavlink_channel_t chan, const mavlink_set_home_position_t* set_home_position) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_set_home_position_send(chan, set_home_position->target_system, set_home_position->latitude, set_home_position->longitude, set_home_position->altitude, set_home_position->x, set_home_position->y, set_home_position->z, set_home_position->q, set_home_position->approach_x, set_home_position->approach_y, set_home_position->approach_z, set_home_position->time_usec); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_HOME_POSITION, (const char *)set_home_position, MAVLINK_MSG_ID_SET_HOME_POSITION_MIN_LEN, MAVLINK_MSG_ID_SET_HOME_POSITION_LEN, MAVLINK_MSG_ID_SET_HOME_POSITION_CRC); -#endif -} - -#if MAVLINK_MSG_ID_SET_HOME_POSITION_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_set_home_position_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, int32_t latitude, int32_t longitude, int32_t altitude, float x, float y, float z, const float *q, float approach_x, float approach_y, float approach_z, uint64_t time_usec) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_int32_t(buf, 0, latitude); - _mav_put_int32_t(buf, 4, longitude); - _mav_put_int32_t(buf, 8, altitude); - _mav_put_float(buf, 12, x); - _mav_put_float(buf, 16, y); - _mav_put_float(buf, 20, z); - _mav_put_float(buf, 40, approach_x); - _mav_put_float(buf, 44, approach_y); - _mav_put_float(buf, 48, approach_z); - _mav_put_uint8_t(buf, 52, target_system); - _mav_put_uint64_t(buf, 53, time_usec); - _mav_put_float_array(buf, 24, q, 4); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_HOME_POSITION, buf, MAVLINK_MSG_ID_SET_HOME_POSITION_MIN_LEN, MAVLINK_MSG_ID_SET_HOME_POSITION_LEN, MAVLINK_MSG_ID_SET_HOME_POSITION_CRC); -#else - mavlink_set_home_position_t *packet = (mavlink_set_home_position_t *)msgbuf; - packet->latitude = latitude; - packet->longitude = longitude; - packet->altitude = altitude; - packet->x = x; - packet->y = y; - packet->z = z; - packet->approach_x = approach_x; - packet->approach_y = approach_y; - packet->approach_z = approach_z; - packet->target_system = target_system; - packet->time_usec = time_usec; - mav_array_memcpy(packet->q, q, sizeof(float)*4); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_HOME_POSITION, (const char *)packet, MAVLINK_MSG_ID_SET_HOME_POSITION_MIN_LEN, MAVLINK_MSG_ID_SET_HOME_POSITION_LEN, MAVLINK_MSG_ID_SET_HOME_POSITION_CRC); -#endif -} -#endif - -#endif - -// MESSAGE SET_HOME_POSITION UNPACKING - - -/** - * @brief Get field target_system from set_home_position message - * - * @return System ID. - */ -static inline uint8_t mavlink_msg_set_home_position_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 52); -} - -/** - * @brief Get field latitude from set_home_position message - * - * @return [degE7] Latitude (WGS84) - */ -static inline int32_t mavlink_msg_set_home_position_get_latitude(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 0); -} - -/** - * @brief Get field longitude from set_home_position message - * - * @return [degE7] Longitude (WGS84) - */ -static inline int32_t mavlink_msg_set_home_position_get_longitude(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 4); -} - -/** - * @brief Get field altitude from set_home_position message - * - * @return [mm] Altitude (MSL). Positive for up. - */ -static inline int32_t mavlink_msg_set_home_position_get_altitude(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 8); -} - -/** - * @brief Get field x from set_home_position message - * - * @return [m] Local X position of this position in the local coordinate frame (NED) - */ -static inline float mavlink_msg_set_home_position_get_x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field y from set_home_position message - * - * @return [m] Local Y position of this position in the local coordinate frame (NED) - */ -static inline float mavlink_msg_set_home_position_get_y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field z from set_home_position message - * - * @return [m] Local Z position of this position in the local coordinate frame (NED: positive "down") - */ -static inline float mavlink_msg_set_home_position_get_z(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Get field q from set_home_position message - * - * @return World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground - */ -static inline uint16_t mavlink_msg_set_home_position_get_q(const mavlink_message_t* msg, float *q) -{ - return _MAV_RETURN_float_array(msg, q, 4, 24); -} - -/** - * @brief Get field approach_x from set_home_position message - * - * @return [m] Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. - */ -static inline float mavlink_msg_set_home_position_get_approach_x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 40); -} - -/** - * @brief Get field approach_y from set_home_position message - * - * @return [m] Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. - */ -static inline float mavlink_msg_set_home_position_get_approach_y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 44); -} - -/** - * @brief Get field approach_z from set_home_position message - * - * @return [m] Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. - */ -static inline float mavlink_msg_set_home_position_get_approach_z(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 48); -} - -/** - * @brief Get field time_usec from set_home_position message - * - * @return [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - */ -static inline uint64_t mavlink_msg_set_home_position_get_time_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 53); -} - -/** - * @brief Decode a set_home_position message into a struct - * - * @param msg The message to decode - * @param set_home_position C-struct to decode the message contents into - */ -static inline void mavlink_msg_set_home_position_decode(const mavlink_message_t* msg, mavlink_set_home_position_t* set_home_position) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - set_home_position->latitude = mavlink_msg_set_home_position_get_latitude(msg); - set_home_position->longitude = mavlink_msg_set_home_position_get_longitude(msg); - set_home_position->altitude = mavlink_msg_set_home_position_get_altitude(msg); - set_home_position->x = mavlink_msg_set_home_position_get_x(msg); - set_home_position->y = mavlink_msg_set_home_position_get_y(msg); - set_home_position->z = mavlink_msg_set_home_position_get_z(msg); - mavlink_msg_set_home_position_get_q(msg, set_home_position->q); - set_home_position->approach_x = mavlink_msg_set_home_position_get_approach_x(msg); - set_home_position->approach_y = mavlink_msg_set_home_position_get_approach_y(msg); - set_home_position->approach_z = mavlink_msg_set_home_position_get_approach_z(msg); - set_home_position->target_system = mavlink_msg_set_home_position_get_target_system(msg); - set_home_position->time_usec = mavlink_msg_set_home_position_get_time_usec(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_SET_HOME_POSITION_LEN? msg->len : MAVLINK_MSG_ID_SET_HOME_POSITION_LEN; - memset(set_home_position, 0, MAVLINK_MSG_ID_SET_HOME_POSITION_LEN); - memcpy(set_home_position, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_set_mode.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_set_mode.h deleted file mode 100644 index 14509122..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_set_mode.h +++ /dev/null @@ -1,263 +0,0 @@ -#pragma once -// MESSAGE SET_MODE PACKING - -#define MAVLINK_MSG_ID_SET_MODE 11 - - -typedef struct __mavlink_set_mode_t { - uint32_t custom_mode; /*< The new autopilot-specific mode. This field can be ignored by an autopilot.*/ - uint8_t target_system; /*< The system setting the mode*/ - uint8_t base_mode; /*< The new base mode.*/ -} mavlink_set_mode_t; - -#define MAVLINK_MSG_ID_SET_MODE_LEN 6 -#define MAVLINK_MSG_ID_SET_MODE_MIN_LEN 6 -#define MAVLINK_MSG_ID_11_LEN 6 -#define MAVLINK_MSG_ID_11_MIN_LEN 6 - -#define MAVLINK_MSG_ID_SET_MODE_CRC 89 -#define MAVLINK_MSG_ID_11_CRC 89 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_SET_MODE { \ - 11, \ - "SET_MODE", \ - 3, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_set_mode_t, target_system) }, \ - { "base_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_set_mode_t, base_mode) }, \ - { "custom_mode", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_set_mode_t, custom_mode) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_SET_MODE { \ - "SET_MODE", \ - 3, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_set_mode_t, target_system) }, \ - { "base_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_set_mode_t, base_mode) }, \ - { "custom_mode", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_set_mode_t, custom_mode) }, \ - } \ -} -#endif - -/** - * @brief Pack a set_mode message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system The system setting the mode - * @param base_mode The new base mode. - * @param custom_mode The new autopilot-specific mode. This field can be ignored by an autopilot. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_set_mode_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t base_mode, uint32_t custom_mode) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SET_MODE_LEN]; - _mav_put_uint32_t(buf, 0, custom_mode); - _mav_put_uint8_t(buf, 4, target_system); - _mav_put_uint8_t(buf, 5, base_mode); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_MODE_LEN); -#else - mavlink_set_mode_t packet; - packet.custom_mode = custom_mode; - packet.target_system = target_system; - packet.base_mode = base_mode; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_MODE_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SET_MODE; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_MODE_MIN_LEN, MAVLINK_MSG_ID_SET_MODE_LEN, MAVLINK_MSG_ID_SET_MODE_CRC); -} - -/** - * @brief Pack a set_mode message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system The system setting the mode - * @param base_mode The new base mode. - * @param custom_mode The new autopilot-specific mode. This field can be ignored by an autopilot. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_set_mode_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t base_mode,uint32_t custom_mode) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SET_MODE_LEN]; - _mav_put_uint32_t(buf, 0, custom_mode); - _mav_put_uint8_t(buf, 4, target_system); - _mav_put_uint8_t(buf, 5, base_mode); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_MODE_LEN); -#else - mavlink_set_mode_t packet; - packet.custom_mode = custom_mode; - packet.target_system = target_system; - packet.base_mode = base_mode; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_MODE_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SET_MODE; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_MODE_MIN_LEN, MAVLINK_MSG_ID_SET_MODE_LEN, MAVLINK_MSG_ID_SET_MODE_CRC); -} - -/** - * @brief Encode a set_mode struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param set_mode C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_set_mode_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_mode_t* set_mode) -{ - return mavlink_msg_set_mode_pack(system_id, component_id, msg, set_mode->target_system, set_mode->base_mode, set_mode->custom_mode); -} - -/** - * @brief Encode a set_mode struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param set_mode C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_set_mode_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_set_mode_t* set_mode) -{ - return mavlink_msg_set_mode_pack_chan(system_id, component_id, chan, msg, set_mode->target_system, set_mode->base_mode, set_mode->custom_mode); -} - -/** - * @brief Send a set_mode message - * @param chan MAVLink channel to send the message - * - * @param target_system The system setting the mode - * @param base_mode The new base mode. - * @param custom_mode The new autopilot-specific mode. This field can be ignored by an autopilot. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_set_mode_send(mavlink_channel_t chan, uint8_t target_system, uint8_t base_mode, uint32_t custom_mode) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SET_MODE_LEN]; - _mav_put_uint32_t(buf, 0, custom_mode); - _mav_put_uint8_t(buf, 4, target_system); - _mav_put_uint8_t(buf, 5, base_mode); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_MODE, buf, MAVLINK_MSG_ID_SET_MODE_MIN_LEN, MAVLINK_MSG_ID_SET_MODE_LEN, MAVLINK_MSG_ID_SET_MODE_CRC); -#else - mavlink_set_mode_t packet; - packet.custom_mode = custom_mode; - packet.target_system = target_system; - packet.base_mode = base_mode; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_MODE, (const char *)&packet, MAVLINK_MSG_ID_SET_MODE_MIN_LEN, MAVLINK_MSG_ID_SET_MODE_LEN, MAVLINK_MSG_ID_SET_MODE_CRC); -#endif -} - -/** - * @brief Send a set_mode message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_set_mode_send_struct(mavlink_channel_t chan, const mavlink_set_mode_t* set_mode) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_set_mode_send(chan, set_mode->target_system, set_mode->base_mode, set_mode->custom_mode); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_MODE, (const char *)set_mode, MAVLINK_MSG_ID_SET_MODE_MIN_LEN, MAVLINK_MSG_ID_SET_MODE_LEN, MAVLINK_MSG_ID_SET_MODE_CRC); -#endif -} - -#if MAVLINK_MSG_ID_SET_MODE_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_set_mode_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t base_mode, uint32_t custom_mode) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, custom_mode); - _mav_put_uint8_t(buf, 4, target_system); - _mav_put_uint8_t(buf, 5, base_mode); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_MODE, buf, MAVLINK_MSG_ID_SET_MODE_MIN_LEN, MAVLINK_MSG_ID_SET_MODE_LEN, MAVLINK_MSG_ID_SET_MODE_CRC); -#else - mavlink_set_mode_t *packet = (mavlink_set_mode_t *)msgbuf; - packet->custom_mode = custom_mode; - packet->target_system = target_system; - packet->base_mode = base_mode; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_MODE, (const char *)packet, MAVLINK_MSG_ID_SET_MODE_MIN_LEN, MAVLINK_MSG_ID_SET_MODE_LEN, MAVLINK_MSG_ID_SET_MODE_CRC); -#endif -} -#endif - -#endif - -// MESSAGE SET_MODE UNPACKING - - -/** - * @brief Get field target_system from set_mode message - * - * @return The system setting the mode - */ -static inline uint8_t mavlink_msg_set_mode_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 4); -} - -/** - * @brief Get field base_mode from set_mode message - * - * @return The new base mode. - */ -static inline uint8_t mavlink_msg_set_mode_get_base_mode(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 5); -} - -/** - * @brief Get field custom_mode from set_mode message - * - * @return The new autopilot-specific mode. This field can be ignored by an autopilot. - */ -static inline uint32_t mavlink_msg_set_mode_get_custom_mode(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Decode a set_mode message into a struct - * - * @param msg The message to decode - * @param set_mode C-struct to decode the message contents into - */ -static inline void mavlink_msg_set_mode_decode(const mavlink_message_t* msg, mavlink_set_mode_t* set_mode) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - set_mode->custom_mode = mavlink_msg_set_mode_get_custom_mode(msg); - set_mode->target_system = mavlink_msg_set_mode_get_target_system(msg); - set_mode->base_mode = mavlink_msg_set_mode_get_base_mode(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_SET_MODE_LEN? msg->len : MAVLINK_MSG_ID_SET_MODE_LEN; - memset(set_mode, 0, MAVLINK_MSG_ID_SET_MODE_LEN); - memcpy(set_mode, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_set_position_target_global_int.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_set_position_target_global_int.h deleted file mode 100644 index 0c314cab..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_set_position_target_global_int.h +++ /dev/null @@ -1,588 +0,0 @@ -#pragma once -// MESSAGE SET_POSITION_TARGET_GLOBAL_INT PACKING - -#define MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT 86 - - -typedef struct __mavlink_set_position_target_global_int_t { - uint32_t time_boot_ms; /*< [ms] Timestamp (time since system boot). The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency.*/ - int32_t lat_int; /*< [degE7] X Position in WGS84 frame*/ - int32_t lon_int; /*< [degE7] Y Position in WGS84 frame*/ - float alt; /*< [m] Altitude (MSL, Relative to home, or AGL - depending on frame)*/ - float vx; /*< [m/s] X velocity in NED frame*/ - float vy; /*< [m/s] Y velocity in NED frame*/ - float vz; /*< [m/s] Z velocity in NED frame*/ - float afx; /*< [m/s/s] X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N*/ - float afy; /*< [m/s/s] Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N*/ - float afz; /*< [m/s/s] Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N*/ - float yaw; /*< [rad] yaw setpoint*/ - float yaw_rate; /*< [rad/s] yaw rate setpoint*/ - uint16_t type_mask; /*< Bitmap to indicate which dimensions should be ignored by the vehicle.*/ - uint8_t target_system; /*< System ID*/ - uint8_t target_component; /*< Component ID*/ - uint8_t coordinate_frame; /*< Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11*/ -} mavlink_set_position_target_global_int_t; - -#define MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN 53 -#define MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_MIN_LEN 53 -#define MAVLINK_MSG_ID_86_LEN 53 -#define MAVLINK_MSG_ID_86_MIN_LEN 53 - -#define MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_CRC 5 -#define MAVLINK_MSG_ID_86_CRC 5 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_SET_POSITION_TARGET_GLOBAL_INT { \ - 86, \ - "SET_POSITION_TARGET_GLOBAL_INT", \ - 16, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_set_position_target_global_int_t, time_boot_ms) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 50, offsetof(mavlink_set_position_target_global_int_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 51, offsetof(mavlink_set_position_target_global_int_t, target_component) }, \ - { "coordinate_frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 52, offsetof(mavlink_set_position_target_global_int_t, coordinate_frame) }, \ - { "type_mask", NULL, MAVLINK_TYPE_UINT16_T, 0, 48, offsetof(mavlink_set_position_target_global_int_t, type_mask) }, \ - { "lat_int", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_set_position_target_global_int_t, lat_int) }, \ - { "lon_int", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_set_position_target_global_int_t, lon_int) }, \ - { "alt", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_set_position_target_global_int_t, alt) }, \ - { "vx", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_set_position_target_global_int_t, vx) }, \ - { "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_set_position_target_global_int_t, vy) }, \ - { "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_set_position_target_global_int_t, vz) }, \ - { "afx", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_set_position_target_global_int_t, afx) }, \ - { "afy", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_set_position_target_global_int_t, afy) }, \ - { "afz", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_set_position_target_global_int_t, afz) }, \ - { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_set_position_target_global_int_t, yaw) }, \ - { "yaw_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_set_position_target_global_int_t, yaw_rate) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_SET_POSITION_TARGET_GLOBAL_INT { \ - "SET_POSITION_TARGET_GLOBAL_INT", \ - 16, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_set_position_target_global_int_t, time_boot_ms) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 50, offsetof(mavlink_set_position_target_global_int_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 51, offsetof(mavlink_set_position_target_global_int_t, target_component) }, \ - { "coordinate_frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 52, offsetof(mavlink_set_position_target_global_int_t, coordinate_frame) }, \ - { "type_mask", NULL, MAVLINK_TYPE_UINT16_T, 0, 48, offsetof(mavlink_set_position_target_global_int_t, type_mask) }, \ - { "lat_int", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_set_position_target_global_int_t, lat_int) }, \ - { "lon_int", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_set_position_target_global_int_t, lon_int) }, \ - { "alt", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_set_position_target_global_int_t, alt) }, \ - { "vx", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_set_position_target_global_int_t, vx) }, \ - { "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_set_position_target_global_int_t, vy) }, \ - { "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_set_position_target_global_int_t, vz) }, \ - { "afx", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_set_position_target_global_int_t, afx) }, \ - { "afy", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_set_position_target_global_int_t, afy) }, \ - { "afz", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_set_position_target_global_int_t, afz) }, \ - { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_set_position_target_global_int_t, yaw) }, \ - { "yaw_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_set_position_target_global_int_t, yaw_rate) }, \ - } \ -} -#endif - -/** - * @brief Pack a set_position_target_global_int message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param time_boot_ms [ms] Timestamp (time since system boot). The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency. - * @param target_system System ID - * @param target_component Component ID - * @param coordinate_frame Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11 - * @param type_mask Bitmap to indicate which dimensions should be ignored by the vehicle. - * @param lat_int [degE7] X Position in WGS84 frame - * @param lon_int [degE7] Y Position in WGS84 frame - * @param alt [m] Altitude (MSL, Relative to home, or AGL - depending on frame) - * @param vx [m/s] X velocity in NED frame - * @param vy [m/s] Y velocity in NED frame - * @param vz [m/s] Z velocity in NED frame - * @param afx [m/s/s] X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param afy [m/s/s] Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param afz [m/s/s] Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param yaw [rad] yaw setpoint - * @param yaw_rate [rad/s] yaw rate setpoint - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_set_position_target_global_int_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint32_t time_boot_ms, uint8_t target_system, uint8_t target_component, uint8_t coordinate_frame, uint16_t type_mask, int32_t lat_int, int32_t lon_int, float alt, float vx, float vy, float vz, float afx, float afy, float afz, float yaw, float yaw_rate) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_int32_t(buf, 4, lat_int); - _mav_put_int32_t(buf, 8, lon_int); - _mav_put_float(buf, 12, alt); - _mav_put_float(buf, 16, vx); - _mav_put_float(buf, 20, vy); - _mav_put_float(buf, 24, vz); - _mav_put_float(buf, 28, afx); - _mav_put_float(buf, 32, afy); - _mav_put_float(buf, 36, afz); - _mav_put_float(buf, 40, yaw); - _mav_put_float(buf, 44, yaw_rate); - _mav_put_uint16_t(buf, 48, type_mask); - _mav_put_uint8_t(buf, 50, target_system); - _mav_put_uint8_t(buf, 51, target_component); - _mav_put_uint8_t(buf, 52, coordinate_frame); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN); -#else - mavlink_set_position_target_global_int_t packet; - packet.time_boot_ms = time_boot_ms; - packet.lat_int = lat_int; - packet.lon_int = lon_int; - packet.alt = alt; - packet.vx = vx; - packet.vy = vy; - packet.vz = vz; - packet.afx = afx; - packet.afy = afy; - packet.afz = afz; - packet.yaw = yaw; - packet.yaw_rate = yaw_rate; - packet.type_mask = type_mask; - packet.target_system = target_system; - packet.target_component = target_component; - packet.coordinate_frame = coordinate_frame; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_MIN_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_CRC); -} - -/** - * @brief Pack a set_position_target_global_int message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_boot_ms [ms] Timestamp (time since system boot). The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency. - * @param target_system System ID - * @param target_component Component ID - * @param coordinate_frame Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11 - * @param type_mask Bitmap to indicate which dimensions should be ignored by the vehicle. - * @param lat_int [degE7] X Position in WGS84 frame - * @param lon_int [degE7] Y Position in WGS84 frame - * @param alt [m] Altitude (MSL, Relative to home, or AGL - depending on frame) - * @param vx [m/s] X velocity in NED frame - * @param vy [m/s] Y velocity in NED frame - * @param vz [m/s] Z velocity in NED frame - * @param afx [m/s/s] X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param afy [m/s/s] Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param afz [m/s/s] Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param yaw [rad] yaw setpoint - * @param yaw_rate [rad/s] yaw rate setpoint - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_set_position_target_global_int_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint32_t time_boot_ms,uint8_t target_system,uint8_t target_component,uint8_t coordinate_frame,uint16_t type_mask,int32_t lat_int,int32_t lon_int,float alt,float vx,float vy,float vz,float afx,float afy,float afz,float yaw,float yaw_rate) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_int32_t(buf, 4, lat_int); - _mav_put_int32_t(buf, 8, lon_int); - _mav_put_float(buf, 12, alt); - _mav_put_float(buf, 16, vx); - _mav_put_float(buf, 20, vy); - _mav_put_float(buf, 24, vz); - _mav_put_float(buf, 28, afx); - _mav_put_float(buf, 32, afy); - _mav_put_float(buf, 36, afz); - _mav_put_float(buf, 40, yaw); - _mav_put_float(buf, 44, yaw_rate); - _mav_put_uint16_t(buf, 48, type_mask); - _mav_put_uint8_t(buf, 50, target_system); - _mav_put_uint8_t(buf, 51, target_component); - _mav_put_uint8_t(buf, 52, coordinate_frame); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN); -#else - mavlink_set_position_target_global_int_t packet; - packet.time_boot_ms = time_boot_ms; - packet.lat_int = lat_int; - packet.lon_int = lon_int; - packet.alt = alt; - packet.vx = vx; - packet.vy = vy; - packet.vz = vz; - packet.afx = afx; - packet.afy = afy; - packet.afz = afz; - packet.yaw = yaw; - packet.yaw_rate = yaw_rate; - packet.type_mask = type_mask; - packet.target_system = target_system; - packet.target_component = target_component; - packet.coordinate_frame = coordinate_frame; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_MIN_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_CRC); -} - -/** - * @brief Encode a set_position_target_global_int struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param set_position_target_global_int C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_set_position_target_global_int_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_position_target_global_int_t* set_position_target_global_int) -{ - return mavlink_msg_set_position_target_global_int_pack(system_id, component_id, msg, set_position_target_global_int->time_boot_ms, set_position_target_global_int->target_system, set_position_target_global_int->target_component, set_position_target_global_int->coordinate_frame, set_position_target_global_int->type_mask, set_position_target_global_int->lat_int, set_position_target_global_int->lon_int, set_position_target_global_int->alt, set_position_target_global_int->vx, set_position_target_global_int->vy, set_position_target_global_int->vz, set_position_target_global_int->afx, set_position_target_global_int->afy, set_position_target_global_int->afz, set_position_target_global_int->yaw, set_position_target_global_int->yaw_rate); -} - -/** - * @brief Encode a set_position_target_global_int struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param set_position_target_global_int C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_set_position_target_global_int_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_set_position_target_global_int_t* set_position_target_global_int) -{ - return mavlink_msg_set_position_target_global_int_pack_chan(system_id, component_id, chan, msg, set_position_target_global_int->time_boot_ms, set_position_target_global_int->target_system, set_position_target_global_int->target_component, set_position_target_global_int->coordinate_frame, set_position_target_global_int->type_mask, set_position_target_global_int->lat_int, set_position_target_global_int->lon_int, set_position_target_global_int->alt, set_position_target_global_int->vx, set_position_target_global_int->vy, set_position_target_global_int->vz, set_position_target_global_int->afx, set_position_target_global_int->afy, set_position_target_global_int->afz, set_position_target_global_int->yaw, set_position_target_global_int->yaw_rate); -} - -/** - * @brief Send a set_position_target_global_int message - * @param chan MAVLink channel to send the message - * - * @param time_boot_ms [ms] Timestamp (time since system boot). The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency. - * @param target_system System ID - * @param target_component Component ID - * @param coordinate_frame Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11 - * @param type_mask Bitmap to indicate which dimensions should be ignored by the vehicle. - * @param lat_int [degE7] X Position in WGS84 frame - * @param lon_int [degE7] Y Position in WGS84 frame - * @param alt [m] Altitude (MSL, Relative to home, or AGL - depending on frame) - * @param vx [m/s] X velocity in NED frame - * @param vy [m/s] Y velocity in NED frame - * @param vz [m/s] Z velocity in NED frame - * @param afx [m/s/s] X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param afy [m/s/s] Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param afz [m/s/s] Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param yaw [rad] yaw setpoint - * @param yaw_rate [rad/s] yaw rate setpoint - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_set_position_target_global_int_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t target_system, uint8_t target_component, uint8_t coordinate_frame, uint16_t type_mask, int32_t lat_int, int32_t lon_int, float alt, float vx, float vy, float vz, float afx, float afy, float afz, float yaw, float yaw_rate) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_int32_t(buf, 4, lat_int); - _mav_put_int32_t(buf, 8, lon_int); - _mav_put_float(buf, 12, alt); - _mav_put_float(buf, 16, vx); - _mav_put_float(buf, 20, vy); - _mav_put_float(buf, 24, vz); - _mav_put_float(buf, 28, afx); - _mav_put_float(buf, 32, afy); - _mav_put_float(buf, 36, afz); - _mav_put_float(buf, 40, yaw); - _mav_put_float(buf, 44, yaw_rate); - _mav_put_uint16_t(buf, 48, type_mask); - _mav_put_uint8_t(buf, 50, target_system); - _mav_put_uint8_t(buf, 51, target_component); - _mav_put_uint8_t(buf, 52, coordinate_frame); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT, buf, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_MIN_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_CRC); -#else - mavlink_set_position_target_global_int_t packet; - packet.time_boot_ms = time_boot_ms; - packet.lat_int = lat_int; - packet.lon_int = lon_int; - packet.alt = alt; - packet.vx = vx; - packet.vy = vy; - packet.vz = vz; - packet.afx = afx; - packet.afy = afy; - packet.afz = afz; - packet.yaw = yaw; - packet.yaw_rate = yaw_rate; - packet.type_mask = type_mask; - packet.target_system = target_system; - packet.target_component = target_component; - packet.coordinate_frame = coordinate_frame; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT, (const char *)&packet, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_MIN_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_CRC); -#endif -} - -/** - * @brief Send a set_position_target_global_int message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_set_position_target_global_int_send_struct(mavlink_channel_t chan, const mavlink_set_position_target_global_int_t* set_position_target_global_int) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_set_position_target_global_int_send(chan, set_position_target_global_int->time_boot_ms, set_position_target_global_int->target_system, set_position_target_global_int->target_component, set_position_target_global_int->coordinate_frame, set_position_target_global_int->type_mask, set_position_target_global_int->lat_int, set_position_target_global_int->lon_int, set_position_target_global_int->alt, set_position_target_global_int->vx, set_position_target_global_int->vy, set_position_target_global_int->vz, set_position_target_global_int->afx, set_position_target_global_int->afy, set_position_target_global_int->afz, set_position_target_global_int->yaw, set_position_target_global_int->yaw_rate); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT, (const char *)set_position_target_global_int, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_MIN_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_CRC); -#endif -} - -#if MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_set_position_target_global_int_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t target_system, uint8_t target_component, uint8_t coordinate_frame, uint16_t type_mask, int32_t lat_int, int32_t lon_int, float alt, float vx, float vy, float vz, float afx, float afy, float afz, float yaw, float yaw_rate) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_int32_t(buf, 4, lat_int); - _mav_put_int32_t(buf, 8, lon_int); - _mav_put_float(buf, 12, alt); - _mav_put_float(buf, 16, vx); - _mav_put_float(buf, 20, vy); - _mav_put_float(buf, 24, vz); - _mav_put_float(buf, 28, afx); - _mav_put_float(buf, 32, afy); - _mav_put_float(buf, 36, afz); - _mav_put_float(buf, 40, yaw); - _mav_put_float(buf, 44, yaw_rate); - _mav_put_uint16_t(buf, 48, type_mask); - _mav_put_uint8_t(buf, 50, target_system); - _mav_put_uint8_t(buf, 51, target_component); - _mav_put_uint8_t(buf, 52, coordinate_frame); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT, buf, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_MIN_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_CRC); -#else - mavlink_set_position_target_global_int_t *packet = (mavlink_set_position_target_global_int_t *)msgbuf; - packet->time_boot_ms = time_boot_ms; - packet->lat_int = lat_int; - packet->lon_int = lon_int; - packet->alt = alt; - packet->vx = vx; - packet->vy = vy; - packet->vz = vz; - packet->afx = afx; - packet->afy = afy; - packet->afz = afz; - packet->yaw = yaw; - packet->yaw_rate = yaw_rate; - packet->type_mask = type_mask; - packet->target_system = target_system; - packet->target_component = target_component; - packet->coordinate_frame = coordinate_frame; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT, (const char *)packet, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_MIN_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_CRC); -#endif -} -#endif - -#endif - -// MESSAGE SET_POSITION_TARGET_GLOBAL_INT UNPACKING - - -/** - * @brief Get field time_boot_ms from set_position_target_global_int message - * - * @return [ms] Timestamp (time since system boot). The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency. - */ -static inline uint32_t mavlink_msg_set_position_target_global_int_get_time_boot_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field target_system from set_position_target_global_int message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_set_position_target_global_int_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 50); -} - -/** - * @brief Get field target_component from set_position_target_global_int message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_set_position_target_global_int_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 51); -} - -/** - * @brief Get field coordinate_frame from set_position_target_global_int message - * - * @return Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11 - */ -static inline uint8_t mavlink_msg_set_position_target_global_int_get_coordinate_frame(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 52); -} - -/** - * @brief Get field type_mask from set_position_target_global_int message - * - * @return Bitmap to indicate which dimensions should be ignored by the vehicle. - */ -static inline uint16_t mavlink_msg_set_position_target_global_int_get_type_mask(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 48); -} - -/** - * @brief Get field lat_int from set_position_target_global_int message - * - * @return [degE7] X Position in WGS84 frame - */ -static inline int32_t mavlink_msg_set_position_target_global_int_get_lat_int(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 4); -} - -/** - * @brief Get field lon_int from set_position_target_global_int message - * - * @return [degE7] Y Position in WGS84 frame - */ -static inline int32_t mavlink_msg_set_position_target_global_int_get_lon_int(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 8); -} - -/** - * @brief Get field alt from set_position_target_global_int message - * - * @return [m] Altitude (MSL, Relative to home, or AGL - depending on frame) - */ -static inline float mavlink_msg_set_position_target_global_int_get_alt(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field vx from set_position_target_global_int message - * - * @return [m/s] X velocity in NED frame - */ -static inline float mavlink_msg_set_position_target_global_int_get_vx(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field vy from set_position_target_global_int message - * - * @return [m/s] Y velocity in NED frame - */ -static inline float mavlink_msg_set_position_target_global_int_get_vy(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Get field vz from set_position_target_global_int message - * - * @return [m/s] Z velocity in NED frame - */ -static inline float mavlink_msg_set_position_target_global_int_get_vz(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Get field afx from set_position_target_global_int message - * - * @return [m/s/s] X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - */ -static inline float mavlink_msg_set_position_target_global_int_get_afx(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 28); -} - -/** - * @brief Get field afy from set_position_target_global_int message - * - * @return [m/s/s] Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - */ -static inline float mavlink_msg_set_position_target_global_int_get_afy(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 32); -} - -/** - * @brief Get field afz from set_position_target_global_int message - * - * @return [m/s/s] Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - */ -static inline float mavlink_msg_set_position_target_global_int_get_afz(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 36); -} - -/** - * @brief Get field yaw from set_position_target_global_int message - * - * @return [rad] yaw setpoint - */ -static inline float mavlink_msg_set_position_target_global_int_get_yaw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 40); -} - -/** - * @brief Get field yaw_rate from set_position_target_global_int message - * - * @return [rad/s] yaw rate setpoint - */ -static inline float mavlink_msg_set_position_target_global_int_get_yaw_rate(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 44); -} - -/** - * @brief Decode a set_position_target_global_int message into a struct - * - * @param msg The message to decode - * @param set_position_target_global_int C-struct to decode the message contents into - */ -static inline void mavlink_msg_set_position_target_global_int_decode(const mavlink_message_t* msg, mavlink_set_position_target_global_int_t* set_position_target_global_int) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - set_position_target_global_int->time_boot_ms = mavlink_msg_set_position_target_global_int_get_time_boot_ms(msg); - set_position_target_global_int->lat_int = mavlink_msg_set_position_target_global_int_get_lat_int(msg); - set_position_target_global_int->lon_int = mavlink_msg_set_position_target_global_int_get_lon_int(msg); - set_position_target_global_int->alt = mavlink_msg_set_position_target_global_int_get_alt(msg); - set_position_target_global_int->vx = mavlink_msg_set_position_target_global_int_get_vx(msg); - set_position_target_global_int->vy = mavlink_msg_set_position_target_global_int_get_vy(msg); - set_position_target_global_int->vz = mavlink_msg_set_position_target_global_int_get_vz(msg); - set_position_target_global_int->afx = mavlink_msg_set_position_target_global_int_get_afx(msg); - set_position_target_global_int->afy = mavlink_msg_set_position_target_global_int_get_afy(msg); - set_position_target_global_int->afz = mavlink_msg_set_position_target_global_int_get_afz(msg); - set_position_target_global_int->yaw = mavlink_msg_set_position_target_global_int_get_yaw(msg); - set_position_target_global_int->yaw_rate = mavlink_msg_set_position_target_global_int_get_yaw_rate(msg); - set_position_target_global_int->type_mask = mavlink_msg_set_position_target_global_int_get_type_mask(msg); - set_position_target_global_int->target_system = mavlink_msg_set_position_target_global_int_get_target_system(msg); - set_position_target_global_int->target_component = mavlink_msg_set_position_target_global_int_get_target_component(msg); - set_position_target_global_int->coordinate_frame = mavlink_msg_set_position_target_global_int_get_coordinate_frame(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN? msg->len : MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN; - memset(set_position_target_global_int, 0, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN); - memcpy(set_position_target_global_int, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_set_position_target_local_ned.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_set_position_target_local_ned.h deleted file mode 100644 index 646bda57..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_set_position_target_local_ned.h +++ /dev/null @@ -1,588 +0,0 @@ -#pragma once -// MESSAGE SET_POSITION_TARGET_LOCAL_NED PACKING - -#define MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED 84 - - -typedef struct __mavlink_set_position_target_local_ned_t { - uint32_t time_boot_ms; /*< [ms] Timestamp (time since system boot).*/ - float x; /*< [m] X Position in NED frame*/ - float y; /*< [m] Y Position in NED frame*/ - float z; /*< [m] Z Position in NED frame (note, altitude is negative in NED)*/ - float vx; /*< [m/s] X velocity in NED frame*/ - float vy; /*< [m/s] Y velocity in NED frame*/ - float vz; /*< [m/s] Z velocity in NED frame*/ - float afx; /*< [m/s/s] X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N*/ - float afy; /*< [m/s/s] Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N*/ - float afz; /*< [m/s/s] Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N*/ - float yaw; /*< [rad] yaw setpoint*/ - float yaw_rate; /*< [rad/s] yaw rate setpoint*/ - uint16_t type_mask; /*< Bitmap to indicate which dimensions should be ignored by the vehicle.*/ - uint8_t target_system; /*< System ID*/ - uint8_t target_component; /*< Component ID*/ - uint8_t coordinate_frame; /*< Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9*/ -} mavlink_set_position_target_local_ned_t; - -#define MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN 53 -#define MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_MIN_LEN 53 -#define MAVLINK_MSG_ID_84_LEN 53 -#define MAVLINK_MSG_ID_84_MIN_LEN 53 - -#define MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_CRC 143 -#define MAVLINK_MSG_ID_84_CRC 143 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_SET_POSITION_TARGET_LOCAL_NED { \ - 84, \ - "SET_POSITION_TARGET_LOCAL_NED", \ - 16, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_set_position_target_local_ned_t, time_boot_ms) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 50, offsetof(mavlink_set_position_target_local_ned_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 51, offsetof(mavlink_set_position_target_local_ned_t, target_component) }, \ - { "coordinate_frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 52, offsetof(mavlink_set_position_target_local_ned_t, coordinate_frame) }, \ - { "type_mask", NULL, MAVLINK_TYPE_UINT16_T, 0, 48, offsetof(mavlink_set_position_target_local_ned_t, type_mask) }, \ - { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_set_position_target_local_ned_t, x) }, \ - { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_set_position_target_local_ned_t, y) }, \ - { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_set_position_target_local_ned_t, z) }, \ - { "vx", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_set_position_target_local_ned_t, vx) }, \ - { "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_set_position_target_local_ned_t, vy) }, \ - { "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_set_position_target_local_ned_t, vz) }, \ - { "afx", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_set_position_target_local_ned_t, afx) }, \ - { "afy", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_set_position_target_local_ned_t, afy) }, \ - { "afz", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_set_position_target_local_ned_t, afz) }, \ - { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_set_position_target_local_ned_t, yaw) }, \ - { "yaw_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_set_position_target_local_ned_t, yaw_rate) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_SET_POSITION_TARGET_LOCAL_NED { \ - "SET_POSITION_TARGET_LOCAL_NED", \ - 16, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_set_position_target_local_ned_t, time_boot_ms) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 50, offsetof(mavlink_set_position_target_local_ned_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 51, offsetof(mavlink_set_position_target_local_ned_t, target_component) }, \ - { "coordinate_frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 52, offsetof(mavlink_set_position_target_local_ned_t, coordinate_frame) }, \ - { "type_mask", NULL, MAVLINK_TYPE_UINT16_T, 0, 48, offsetof(mavlink_set_position_target_local_ned_t, type_mask) }, \ - { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_set_position_target_local_ned_t, x) }, \ - { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_set_position_target_local_ned_t, y) }, \ - { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_set_position_target_local_ned_t, z) }, \ - { "vx", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_set_position_target_local_ned_t, vx) }, \ - { "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_set_position_target_local_ned_t, vy) }, \ - { "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_set_position_target_local_ned_t, vz) }, \ - { "afx", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_set_position_target_local_ned_t, afx) }, \ - { "afy", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_set_position_target_local_ned_t, afy) }, \ - { "afz", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_set_position_target_local_ned_t, afz) }, \ - { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_set_position_target_local_ned_t, yaw) }, \ - { "yaw_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_set_position_target_local_ned_t, yaw_rate) }, \ - } \ -} -#endif - -/** - * @brief Pack a set_position_target_local_ned message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param time_boot_ms [ms] Timestamp (time since system boot). - * @param target_system System ID - * @param target_component Component ID - * @param coordinate_frame Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9 - * @param type_mask Bitmap to indicate which dimensions should be ignored by the vehicle. - * @param x [m] X Position in NED frame - * @param y [m] Y Position in NED frame - * @param z [m] Z Position in NED frame (note, altitude is negative in NED) - * @param vx [m/s] X velocity in NED frame - * @param vy [m/s] Y velocity in NED frame - * @param vz [m/s] Z velocity in NED frame - * @param afx [m/s/s] X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param afy [m/s/s] Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param afz [m/s/s] Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param yaw [rad] yaw setpoint - * @param yaw_rate [rad/s] yaw rate setpoint - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_set_position_target_local_ned_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint32_t time_boot_ms, uint8_t target_system, uint8_t target_component, uint8_t coordinate_frame, uint16_t type_mask, float x, float y, float z, float vx, float vy, float vz, float afx, float afy, float afz, float yaw, float yaw_rate) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, x); - _mav_put_float(buf, 8, y); - _mav_put_float(buf, 12, z); - _mav_put_float(buf, 16, vx); - _mav_put_float(buf, 20, vy); - _mav_put_float(buf, 24, vz); - _mav_put_float(buf, 28, afx); - _mav_put_float(buf, 32, afy); - _mav_put_float(buf, 36, afz); - _mav_put_float(buf, 40, yaw); - _mav_put_float(buf, 44, yaw_rate); - _mav_put_uint16_t(buf, 48, type_mask); - _mav_put_uint8_t(buf, 50, target_system); - _mav_put_uint8_t(buf, 51, target_component); - _mav_put_uint8_t(buf, 52, coordinate_frame); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN); -#else - mavlink_set_position_target_local_ned_t packet; - packet.time_boot_ms = time_boot_ms; - packet.x = x; - packet.y = y; - packet.z = z; - packet.vx = vx; - packet.vy = vy; - packet.vz = vz; - packet.afx = afx; - packet.afy = afy; - packet.afz = afz; - packet.yaw = yaw; - packet.yaw_rate = yaw_rate; - packet.type_mask = type_mask; - packet.target_system = target_system; - packet.target_component = target_component; - packet.coordinate_frame = coordinate_frame; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_MIN_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_CRC); -} - -/** - * @brief Pack a set_position_target_local_ned message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_boot_ms [ms] Timestamp (time since system boot). - * @param target_system System ID - * @param target_component Component ID - * @param coordinate_frame Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9 - * @param type_mask Bitmap to indicate which dimensions should be ignored by the vehicle. - * @param x [m] X Position in NED frame - * @param y [m] Y Position in NED frame - * @param z [m] Z Position in NED frame (note, altitude is negative in NED) - * @param vx [m/s] X velocity in NED frame - * @param vy [m/s] Y velocity in NED frame - * @param vz [m/s] Z velocity in NED frame - * @param afx [m/s/s] X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param afy [m/s/s] Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param afz [m/s/s] Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param yaw [rad] yaw setpoint - * @param yaw_rate [rad/s] yaw rate setpoint - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_set_position_target_local_ned_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint32_t time_boot_ms,uint8_t target_system,uint8_t target_component,uint8_t coordinate_frame,uint16_t type_mask,float x,float y,float z,float vx,float vy,float vz,float afx,float afy,float afz,float yaw,float yaw_rate) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, x); - _mav_put_float(buf, 8, y); - _mav_put_float(buf, 12, z); - _mav_put_float(buf, 16, vx); - _mav_put_float(buf, 20, vy); - _mav_put_float(buf, 24, vz); - _mav_put_float(buf, 28, afx); - _mav_put_float(buf, 32, afy); - _mav_put_float(buf, 36, afz); - _mav_put_float(buf, 40, yaw); - _mav_put_float(buf, 44, yaw_rate); - _mav_put_uint16_t(buf, 48, type_mask); - _mav_put_uint8_t(buf, 50, target_system); - _mav_put_uint8_t(buf, 51, target_component); - _mav_put_uint8_t(buf, 52, coordinate_frame); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN); -#else - mavlink_set_position_target_local_ned_t packet; - packet.time_boot_ms = time_boot_ms; - packet.x = x; - packet.y = y; - packet.z = z; - packet.vx = vx; - packet.vy = vy; - packet.vz = vz; - packet.afx = afx; - packet.afy = afy; - packet.afz = afz; - packet.yaw = yaw; - packet.yaw_rate = yaw_rate; - packet.type_mask = type_mask; - packet.target_system = target_system; - packet.target_component = target_component; - packet.coordinate_frame = coordinate_frame; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_MIN_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_CRC); -} - -/** - * @brief Encode a set_position_target_local_ned struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param set_position_target_local_ned C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_set_position_target_local_ned_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_position_target_local_ned_t* set_position_target_local_ned) -{ - return mavlink_msg_set_position_target_local_ned_pack(system_id, component_id, msg, set_position_target_local_ned->time_boot_ms, set_position_target_local_ned->target_system, set_position_target_local_ned->target_component, set_position_target_local_ned->coordinate_frame, set_position_target_local_ned->type_mask, set_position_target_local_ned->x, set_position_target_local_ned->y, set_position_target_local_ned->z, set_position_target_local_ned->vx, set_position_target_local_ned->vy, set_position_target_local_ned->vz, set_position_target_local_ned->afx, set_position_target_local_ned->afy, set_position_target_local_ned->afz, set_position_target_local_ned->yaw, set_position_target_local_ned->yaw_rate); -} - -/** - * @brief Encode a set_position_target_local_ned struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param set_position_target_local_ned C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_set_position_target_local_ned_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_set_position_target_local_ned_t* set_position_target_local_ned) -{ - return mavlink_msg_set_position_target_local_ned_pack_chan(system_id, component_id, chan, msg, set_position_target_local_ned->time_boot_ms, set_position_target_local_ned->target_system, set_position_target_local_ned->target_component, set_position_target_local_ned->coordinate_frame, set_position_target_local_ned->type_mask, set_position_target_local_ned->x, set_position_target_local_ned->y, set_position_target_local_ned->z, set_position_target_local_ned->vx, set_position_target_local_ned->vy, set_position_target_local_ned->vz, set_position_target_local_ned->afx, set_position_target_local_ned->afy, set_position_target_local_ned->afz, set_position_target_local_ned->yaw, set_position_target_local_ned->yaw_rate); -} - -/** - * @brief Send a set_position_target_local_ned message - * @param chan MAVLink channel to send the message - * - * @param time_boot_ms [ms] Timestamp (time since system boot). - * @param target_system System ID - * @param target_component Component ID - * @param coordinate_frame Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9 - * @param type_mask Bitmap to indicate which dimensions should be ignored by the vehicle. - * @param x [m] X Position in NED frame - * @param y [m] Y Position in NED frame - * @param z [m] Z Position in NED frame (note, altitude is negative in NED) - * @param vx [m/s] X velocity in NED frame - * @param vy [m/s] Y velocity in NED frame - * @param vz [m/s] Z velocity in NED frame - * @param afx [m/s/s] X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param afy [m/s/s] Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param afz [m/s/s] Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - * @param yaw [rad] yaw setpoint - * @param yaw_rate [rad/s] yaw rate setpoint - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_set_position_target_local_ned_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t target_system, uint8_t target_component, uint8_t coordinate_frame, uint16_t type_mask, float x, float y, float z, float vx, float vy, float vz, float afx, float afy, float afz, float yaw, float yaw_rate) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, x); - _mav_put_float(buf, 8, y); - _mav_put_float(buf, 12, z); - _mav_put_float(buf, 16, vx); - _mav_put_float(buf, 20, vy); - _mav_put_float(buf, 24, vz); - _mav_put_float(buf, 28, afx); - _mav_put_float(buf, 32, afy); - _mav_put_float(buf, 36, afz); - _mav_put_float(buf, 40, yaw); - _mav_put_float(buf, 44, yaw_rate); - _mav_put_uint16_t(buf, 48, type_mask); - _mav_put_uint8_t(buf, 50, target_system); - _mav_put_uint8_t(buf, 51, target_component); - _mav_put_uint8_t(buf, 52, coordinate_frame); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED, buf, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_MIN_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_CRC); -#else - mavlink_set_position_target_local_ned_t packet; - packet.time_boot_ms = time_boot_ms; - packet.x = x; - packet.y = y; - packet.z = z; - packet.vx = vx; - packet.vy = vy; - packet.vz = vz; - packet.afx = afx; - packet.afy = afy; - packet.afz = afz; - packet.yaw = yaw; - packet.yaw_rate = yaw_rate; - packet.type_mask = type_mask; - packet.target_system = target_system; - packet.target_component = target_component; - packet.coordinate_frame = coordinate_frame; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED, (const char *)&packet, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_MIN_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_CRC); -#endif -} - -/** - * @brief Send a set_position_target_local_ned message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_set_position_target_local_ned_send_struct(mavlink_channel_t chan, const mavlink_set_position_target_local_ned_t* set_position_target_local_ned) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_set_position_target_local_ned_send(chan, set_position_target_local_ned->time_boot_ms, set_position_target_local_ned->target_system, set_position_target_local_ned->target_component, set_position_target_local_ned->coordinate_frame, set_position_target_local_ned->type_mask, set_position_target_local_ned->x, set_position_target_local_ned->y, set_position_target_local_ned->z, set_position_target_local_ned->vx, set_position_target_local_ned->vy, set_position_target_local_ned->vz, set_position_target_local_ned->afx, set_position_target_local_ned->afy, set_position_target_local_ned->afz, set_position_target_local_ned->yaw, set_position_target_local_ned->yaw_rate); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED, (const char *)set_position_target_local_ned, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_MIN_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_CRC); -#endif -} - -#if MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_set_position_target_local_ned_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t target_system, uint8_t target_component, uint8_t coordinate_frame, uint16_t type_mask, float x, float y, float z, float vx, float vy, float vz, float afx, float afy, float afz, float yaw, float yaw_rate) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, x); - _mav_put_float(buf, 8, y); - _mav_put_float(buf, 12, z); - _mav_put_float(buf, 16, vx); - _mav_put_float(buf, 20, vy); - _mav_put_float(buf, 24, vz); - _mav_put_float(buf, 28, afx); - _mav_put_float(buf, 32, afy); - _mav_put_float(buf, 36, afz); - _mav_put_float(buf, 40, yaw); - _mav_put_float(buf, 44, yaw_rate); - _mav_put_uint16_t(buf, 48, type_mask); - _mav_put_uint8_t(buf, 50, target_system); - _mav_put_uint8_t(buf, 51, target_component); - _mav_put_uint8_t(buf, 52, coordinate_frame); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED, buf, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_MIN_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_CRC); -#else - mavlink_set_position_target_local_ned_t *packet = (mavlink_set_position_target_local_ned_t *)msgbuf; - packet->time_boot_ms = time_boot_ms; - packet->x = x; - packet->y = y; - packet->z = z; - packet->vx = vx; - packet->vy = vy; - packet->vz = vz; - packet->afx = afx; - packet->afy = afy; - packet->afz = afz; - packet->yaw = yaw; - packet->yaw_rate = yaw_rate; - packet->type_mask = type_mask; - packet->target_system = target_system; - packet->target_component = target_component; - packet->coordinate_frame = coordinate_frame; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED, (const char *)packet, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_MIN_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_CRC); -#endif -} -#endif - -#endif - -// MESSAGE SET_POSITION_TARGET_LOCAL_NED UNPACKING - - -/** - * @brief Get field time_boot_ms from set_position_target_local_ned message - * - * @return [ms] Timestamp (time since system boot). - */ -static inline uint32_t mavlink_msg_set_position_target_local_ned_get_time_boot_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field target_system from set_position_target_local_ned message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_set_position_target_local_ned_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 50); -} - -/** - * @brief Get field target_component from set_position_target_local_ned message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_set_position_target_local_ned_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 51); -} - -/** - * @brief Get field coordinate_frame from set_position_target_local_ned message - * - * @return Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9 - */ -static inline uint8_t mavlink_msg_set_position_target_local_ned_get_coordinate_frame(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 52); -} - -/** - * @brief Get field type_mask from set_position_target_local_ned message - * - * @return Bitmap to indicate which dimensions should be ignored by the vehicle. - */ -static inline uint16_t mavlink_msg_set_position_target_local_ned_get_type_mask(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 48); -} - -/** - * @brief Get field x from set_position_target_local_ned message - * - * @return [m] X Position in NED frame - */ -static inline float mavlink_msg_set_position_target_local_ned_get_x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 4); -} - -/** - * @brief Get field y from set_position_target_local_ned message - * - * @return [m] Y Position in NED frame - */ -static inline float mavlink_msg_set_position_target_local_ned_get_y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field z from set_position_target_local_ned message - * - * @return [m] Z Position in NED frame (note, altitude is negative in NED) - */ -static inline float mavlink_msg_set_position_target_local_ned_get_z(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field vx from set_position_target_local_ned message - * - * @return [m/s] X velocity in NED frame - */ -static inline float mavlink_msg_set_position_target_local_ned_get_vx(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field vy from set_position_target_local_ned message - * - * @return [m/s] Y velocity in NED frame - */ -static inline float mavlink_msg_set_position_target_local_ned_get_vy(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Get field vz from set_position_target_local_ned message - * - * @return [m/s] Z velocity in NED frame - */ -static inline float mavlink_msg_set_position_target_local_ned_get_vz(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Get field afx from set_position_target_local_ned message - * - * @return [m/s/s] X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - */ -static inline float mavlink_msg_set_position_target_local_ned_get_afx(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 28); -} - -/** - * @brief Get field afy from set_position_target_local_ned message - * - * @return [m/s/s] Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - */ -static inline float mavlink_msg_set_position_target_local_ned_get_afy(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 32); -} - -/** - * @brief Get field afz from set_position_target_local_ned message - * - * @return [m/s/s] Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - */ -static inline float mavlink_msg_set_position_target_local_ned_get_afz(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 36); -} - -/** - * @brief Get field yaw from set_position_target_local_ned message - * - * @return [rad] yaw setpoint - */ -static inline float mavlink_msg_set_position_target_local_ned_get_yaw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 40); -} - -/** - * @brief Get field yaw_rate from set_position_target_local_ned message - * - * @return [rad/s] yaw rate setpoint - */ -static inline float mavlink_msg_set_position_target_local_ned_get_yaw_rate(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 44); -} - -/** - * @brief Decode a set_position_target_local_ned message into a struct - * - * @param msg The message to decode - * @param set_position_target_local_ned C-struct to decode the message contents into - */ -static inline void mavlink_msg_set_position_target_local_ned_decode(const mavlink_message_t* msg, mavlink_set_position_target_local_ned_t* set_position_target_local_ned) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - set_position_target_local_ned->time_boot_ms = mavlink_msg_set_position_target_local_ned_get_time_boot_ms(msg); - set_position_target_local_ned->x = mavlink_msg_set_position_target_local_ned_get_x(msg); - set_position_target_local_ned->y = mavlink_msg_set_position_target_local_ned_get_y(msg); - set_position_target_local_ned->z = mavlink_msg_set_position_target_local_ned_get_z(msg); - set_position_target_local_ned->vx = mavlink_msg_set_position_target_local_ned_get_vx(msg); - set_position_target_local_ned->vy = mavlink_msg_set_position_target_local_ned_get_vy(msg); - set_position_target_local_ned->vz = mavlink_msg_set_position_target_local_ned_get_vz(msg); - set_position_target_local_ned->afx = mavlink_msg_set_position_target_local_ned_get_afx(msg); - set_position_target_local_ned->afy = mavlink_msg_set_position_target_local_ned_get_afy(msg); - set_position_target_local_ned->afz = mavlink_msg_set_position_target_local_ned_get_afz(msg); - set_position_target_local_ned->yaw = mavlink_msg_set_position_target_local_ned_get_yaw(msg); - set_position_target_local_ned->yaw_rate = mavlink_msg_set_position_target_local_ned_get_yaw_rate(msg); - set_position_target_local_ned->type_mask = mavlink_msg_set_position_target_local_ned_get_type_mask(msg); - set_position_target_local_ned->target_system = mavlink_msg_set_position_target_local_ned_get_target_system(msg); - set_position_target_local_ned->target_component = mavlink_msg_set_position_target_local_ned_get_target_component(msg); - set_position_target_local_ned->coordinate_frame = mavlink_msg_set_position_target_local_ned_get_coordinate_frame(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN? msg->len : MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN; - memset(set_position_target_local_ned, 0, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN); - memcpy(set_position_target_local_ned, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_setup_signing.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_setup_signing.h deleted file mode 100644 index 40b2feed..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_setup_signing.h +++ /dev/null @@ -1,280 +0,0 @@ -#pragma once -// MESSAGE SETUP_SIGNING PACKING - -#define MAVLINK_MSG_ID_SETUP_SIGNING 256 - - -typedef struct __mavlink_setup_signing_t { - uint64_t initial_timestamp; /*< initial timestamp*/ - uint8_t target_system; /*< system id of the target*/ - uint8_t target_component; /*< component ID of the target*/ - uint8_t secret_key[32]; /*< signing key*/ -} mavlink_setup_signing_t; - -#define MAVLINK_MSG_ID_SETUP_SIGNING_LEN 42 -#define MAVLINK_MSG_ID_SETUP_SIGNING_MIN_LEN 42 -#define MAVLINK_MSG_ID_256_LEN 42 -#define MAVLINK_MSG_ID_256_MIN_LEN 42 - -#define MAVLINK_MSG_ID_SETUP_SIGNING_CRC 71 -#define MAVLINK_MSG_ID_256_CRC 71 - -#define MAVLINK_MSG_SETUP_SIGNING_FIELD_SECRET_KEY_LEN 32 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_SETUP_SIGNING { \ - 256, \ - "SETUP_SIGNING", \ - 4, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_setup_signing_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 9, offsetof(mavlink_setup_signing_t, target_component) }, \ - { "secret_key", NULL, MAVLINK_TYPE_UINT8_T, 32, 10, offsetof(mavlink_setup_signing_t, secret_key) }, \ - { "initial_timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_setup_signing_t, initial_timestamp) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_SETUP_SIGNING { \ - "SETUP_SIGNING", \ - 4, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_setup_signing_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 9, offsetof(mavlink_setup_signing_t, target_component) }, \ - { "secret_key", NULL, MAVLINK_TYPE_UINT8_T, 32, 10, offsetof(mavlink_setup_signing_t, secret_key) }, \ - { "initial_timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_setup_signing_t, initial_timestamp) }, \ - } \ -} -#endif - -/** - * @brief Pack a setup_signing message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system system id of the target - * @param target_component component ID of the target - * @param secret_key signing key - * @param initial_timestamp initial timestamp - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_setup_signing_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component, const uint8_t *secret_key, uint64_t initial_timestamp) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SETUP_SIGNING_LEN]; - _mav_put_uint64_t(buf, 0, initial_timestamp); - _mav_put_uint8_t(buf, 8, target_system); - _mav_put_uint8_t(buf, 9, target_component); - _mav_put_uint8_t_array(buf, 10, secret_key, 32); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SETUP_SIGNING_LEN); -#else - mavlink_setup_signing_t packet; - packet.initial_timestamp = initial_timestamp; - packet.target_system = target_system; - packet.target_component = target_component; - mav_array_memcpy(packet.secret_key, secret_key, sizeof(uint8_t)*32); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SETUP_SIGNING_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SETUP_SIGNING; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SETUP_SIGNING_MIN_LEN, MAVLINK_MSG_ID_SETUP_SIGNING_LEN, MAVLINK_MSG_ID_SETUP_SIGNING_CRC); -} - -/** - * @brief Pack a setup_signing message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system system id of the target - * @param target_component component ID of the target - * @param secret_key signing key - * @param initial_timestamp initial timestamp - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_setup_signing_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component,const uint8_t *secret_key,uint64_t initial_timestamp) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SETUP_SIGNING_LEN]; - _mav_put_uint64_t(buf, 0, initial_timestamp); - _mav_put_uint8_t(buf, 8, target_system); - _mav_put_uint8_t(buf, 9, target_component); - _mav_put_uint8_t_array(buf, 10, secret_key, 32); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SETUP_SIGNING_LEN); -#else - mavlink_setup_signing_t packet; - packet.initial_timestamp = initial_timestamp; - packet.target_system = target_system; - packet.target_component = target_component; - mav_array_memcpy(packet.secret_key, secret_key, sizeof(uint8_t)*32); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SETUP_SIGNING_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SETUP_SIGNING; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SETUP_SIGNING_MIN_LEN, MAVLINK_MSG_ID_SETUP_SIGNING_LEN, MAVLINK_MSG_ID_SETUP_SIGNING_CRC); -} - -/** - * @brief Encode a setup_signing struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param setup_signing C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_setup_signing_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_setup_signing_t* setup_signing) -{ - return mavlink_msg_setup_signing_pack(system_id, component_id, msg, setup_signing->target_system, setup_signing->target_component, setup_signing->secret_key, setup_signing->initial_timestamp); -} - -/** - * @brief Encode a setup_signing struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param setup_signing C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_setup_signing_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_setup_signing_t* setup_signing) -{ - return mavlink_msg_setup_signing_pack_chan(system_id, component_id, chan, msg, setup_signing->target_system, setup_signing->target_component, setup_signing->secret_key, setup_signing->initial_timestamp); -} - -/** - * @brief Send a setup_signing message - * @param chan MAVLink channel to send the message - * - * @param target_system system id of the target - * @param target_component component ID of the target - * @param secret_key signing key - * @param initial_timestamp initial timestamp - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_setup_signing_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, const uint8_t *secret_key, uint64_t initial_timestamp) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SETUP_SIGNING_LEN]; - _mav_put_uint64_t(buf, 0, initial_timestamp); - _mav_put_uint8_t(buf, 8, target_system); - _mav_put_uint8_t(buf, 9, target_component); - _mav_put_uint8_t_array(buf, 10, secret_key, 32); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SETUP_SIGNING, buf, MAVLINK_MSG_ID_SETUP_SIGNING_MIN_LEN, MAVLINK_MSG_ID_SETUP_SIGNING_LEN, MAVLINK_MSG_ID_SETUP_SIGNING_CRC); -#else - mavlink_setup_signing_t packet; - packet.initial_timestamp = initial_timestamp; - packet.target_system = target_system; - packet.target_component = target_component; - mav_array_memcpy(packet.secret_key, secret_key, sizeof(uint8_t)*32); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SETUP_SIGNING, (const char *)&packet, MAVLINK_MSG_ID_SETUP_SIGNING_MIN_LEN, MAVLINK_MSG_ID_SETUP_SIGNING_LEN, MAVLINK_MSG_ID_SETUP_SIGNING_CRC); -#endif -} - -/** - * @brief Send a setup_signing message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_setup_signing_send_struct(mavlink_channel_t chan, const mavlink_setup_signing_t* setup_signing) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_setup_signing_send(chan, setup_signing->target_system, setup_signing->target_component, setup_signing->secret_key, setup_signing->initial_timestamp); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SETUP_SIGNING, (const char *)setup_signing, MAVLINK_MSG_ID_SETUP_SIGNING_MIN_LEN, MAVLINK_MSG_ID_SETUP_SIGNING_LEN, MAVLINK_MSG_ID_SETUP_SIGNING_CRC); -#endif -} - -#if MAVLINK_MSG_ID_SETUP_SIGNING_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_setup_signing_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, const uint8_t *secret_key, uint64_t initial_timestamp) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, initial_timestamp); - _mav_put_uint8_t(buf, 8, target_system); - _mav_put_uint8_t(buf, 9, target_component); - _mav_put_uint8_t_array(buf, 10, secret_key, 32); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SETUP_SIGNING, buf, MAVLINK_MSG_ID_SETUP_SIGNING_MIN_LEN, MAVLINK_MSG_ID_SETUP_SIGNING_LEN, MAVLINK_MSG_ID_SETUP_SIGNING_CRC); -#else - mavlink_setup_signing_t *packet = (mavlink_setup_signing_t *)msgbuf; - packet->initial_timestamp = initial_timestamp; - packet->target_system = target_system; - packet->target_component = target_component; - mav_array_memcpy(packet->secret_key, secret_key, sizeof(uint8_t)*32); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SETUP_SIGNING, (const char *)packet, MAVLINK_MSG_ID_SETUP_SIGNING_MIN_LEN, MAVLINK_MSG_ID_SETUP_SIGNING_LEN, MAVLINK_MSG_ID_SETUP_SIGNING_CRC); -#endif -} -#endif - -#endif - -// MESSAGE SETUP_SIGNING UNPACKING - - -/** - * @brief Get field target_system from setup_signing message - * - * @return system id of the target - */ -static inline uint8_t mavlink_msg_setup_signing_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 8); -} - -/** - * @brief Get field target_component from setup_signing message - * - * @return component ID of the target - */ -static inline uint8_t mavlink_msg_setup_signing_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 9); -} - -/** - * @brief Get field secret_key from setup_signing message - * - * @return signing key - */ -static inline uint16_t mavlink_msg_setup_signing_get_secret_key(const mavlink_message_t* msg, uint8_t *secret_key) -{ - return _MAV_RETURN_uint8_t_array(msg, secret_key, 32, 10); -} - -/** - * @brief Get field initial_timestamp from setup_signing message - * - * @return initial timestamp - */ -static inline uint64_t mavlink_msg_setup_signing_get_initial_timestamp(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Decode a setup_signing message into a struct - * - * @param msg The message to decode - * @param setup_signing C-struct to decode the message contents into - */ -static inline void mavlink_msg_setup_signing_decode(const mavlink_message_t* msg, mavlink_setup_signing_t* setup_signing) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - setup_signing->initial_timestamp = mavlink_msg_setup_signing_get_initial_timestamp(msg); - setup_signing->target_system = mavlink_msg_setup_signing_get_target_system(msg); - setup_signing->target_component = mavlink_msg_setup_signing_get_target_component(msg); - mavlink_msg_setup_signing_get_secret_key(msg, setup_signing->secret_key); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_SETUP_SIGNING_LEN? msg->len : MAVLINK_MSG_ID_SETUP_SIGNING_LEN; - memset(setup_signing, 0, MAVLINK_MSG_ID_SETUP_SIGNING_LEN); - memcpy(setup_signing, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_sim_state.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_sim_state.h deleted file mode 100644 index 3442f1a0..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_sim_state.h +++ /dev/null @@ -1,763 +0,0 @@ -#pragma once -// MESSAGE SIM_STATE PACKING - -#define MAVLINK_MSG_ID_SIM_STATE 108 - - -typedef struct __mavlink_sim_state_t { - float q1; /*< True attitude quaternion component 1, w (1 in null-rotation)*/ - float q2; /*< True attitude quaternion component 2, x (0 in null-rotation)*/ - float q3; /*< True attitude quaternion component 3, y (0 in null-rotation)*/ - float q4; /*< True attitude quaternion component 4, z (0 in null-rotation)*/ - float roll; /*< Attitude roll expressed as Euler angles, not recommended except for human-readable outputs*/ - float pitch; /*< Attitude pitch expressed as Euler angles, not recommended except for human-readable outputs*/ - float yaw; /*< Attitude yaw expressed as Euler angles, not recommended except for human-readable outputs*/ - float xacc; /*< [m/s/s] X acceleration*/ - float yacc; /*< [m/s/s] Y acceleration*/ - float zacc; /*< [m/s/s] Z acceleration*/ - float xgyro; /*< [rad/s] Angular speed around X axis*/ - float ygyro; /*< [rad/s] Angular speed around Y axis*/ - float zgyro; /*< [rad/s] Angular speed around Z axis*/ - float lat; /*< [deg] Latitude (lower precision). Both this and the lat_int field should be set.*/ - float lon; /*< [deg] Longitude (lower precision). Both this and the lon_int field should be set.*/ - float alt; /*< [m] Altitude*/ - float std_dev_horz; /*< Horizontal position standard deviation*/ - float std_dev_vert; /*< Vertical position standard deviation*/ - float vn; /*< [m/s] True velocity in north direction in earth-fixed NED frame*/ - float ve; /*< [m/s] True velocity in east direction in earth-fixed NED frame*/ - float vd; /*< [m/s] True velocity in down direction in earth-fixed NED frame*/ - int32_t lat_int; /*< [degE7] Latitude (higher precision). If 0, recipients should use the lat field value (otherwise this field is preferred).*/ - int32_t lon_int; /*< [degE7] Longitude (higher precision). If 0, recipients should use the lon field value (otherwise this field is preferred).*/ -} mavlink_sim_state_t; - -#define MAVLINK_MSG_ID_SIM_STATE_LEN 92 -#define MAVLINK_MSG_ID_SIM_STATE_MIN_LEN 84 -#define MAVLINK_MSG_ID_108_LEN 92 -#define MAVLINK_MSG_ID_108_MIN_LEN 84 - -#define MAVLINK_MSG_ID_SIM_STATE_CRC 32 -#define MAVLINK_MSG_ID_108_CRC 32 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_SIM_STATE { \ - 108, \ - "SIM_STATE", \ - 23, \ - { { "q1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_sim_state_t, q1) }, \ - { "q2", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_sim_state_t, q2) }, \ - { "q3", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_sim_state_t, q3) }, \ - { "q4", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_sim_state_t, q4) }, \ - { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_sim_state_t, roll) }, \ - { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_sim_state_t, pitch) }, \ - { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_sim_state_t, yaw) }, \ - { "xacc", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_sim_state_t, xacc) }, \ - { "yacc", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_sim_state_t, yacc) }, \ - { "zacc", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_sim_state_t, zacc) }, \ - { "xgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_sim_state_t, xgyro) }, \ - { "ygyro", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_sim_state_t, ygyro) }, \ - { "zgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_sim_state_t, zgyro) }, \ - { "lat", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_sim_state_t, lat) }, \ - { "lon", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_sim_state_t, lon) }, \ - { "alt", NULL, MAVLINK_TYPE_FLOAT, 0, 60, offsetof(mavlink_sim_state_t, alt) }, \ - { "std_dev_horz", NULL, MAVLINK_TYPE_FLOAT, 0, 64, offsetof(mavlink_sim_state_t, std_dev_horz) }, \ - { "std_dev_vert", NULL, MAVLINK_TYPE_FLOAT, 0, 68, offsetof(mavlink_sim_state_t, std_dev_vert) }, \ - { "vn", NULL, MAVLINK_TYPE_FLOAT, 0, 72, offsetof(mavlink_sim_state_t, vn) }, \ - { "ve", NULL, MAVLINK_TYPE_FLOAT, 0, 76, offsetof(mavlink_sim_state_t, ve) }, \ - { "vd", NULL, MAVLINK_TYPE_FLOAT, 0, 80, offsetof(mavlink_sim_state_t, vd) }, \ - { "lat_int", NULL, MAVLINK_TYPE_INT32_T, 0, 84, offsetof(mavlink_sim_state_t, lat_int) }, \ - { "lon_int", NULL, MAVLINK_TYPE_INT32_T, 0, 88, offsetof(mavlink_sim_state_t, lon_int) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_SIM_STATE { \ - "SIM_STATE", \ - 23, \ - { { "q1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_sim_state_t, q1) }, \ - { "q2", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_sim_state_t, q2) }, \ - { "q3", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_sim_state_t, q3) }, \ - { "q4", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_sim_state_t, q4) }, \ - { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_sim_state_t, roll) }, \ - { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_sim_state_t, pitch) }, \ - { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_sim_state_t, yaw) }, \ - { "xacc", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_sim_state_t, xacc) }, \ - { "yacc", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_sim_state_t, yacc) }, \ - { "zacc", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_sim_state_t, zacc) }, \ - { "xgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_sim_state_t, xgyro) }, \ - { "ygyro", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_sim_state_t, ygyro) }, \ - { "zgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_sim_state_t, zgyro) }, \ - { "lat", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_sim_state_t, lat) }, \ - { "lon", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_sim_state_t, lon) }, \ - { "alt", NULL, MAVLINK_TYPE_FLOAT, 0, 60, offsetof(mavlink_sim_state_t, alt) }, \ - { "std_dev_horz", NULL, MAVLINK_TYPE_FLOAT, 0, 64, offsetof(mavlink_sim_state_t, std_dev_horz) }, \ - { "std_dev_vert", NULL, MAVLINK_TYPE_FLOAT, 0, 68, offsetof(mavlink_sim_state_t, std_dev_vert) }, \ - { "vn", NULL, MAVLINK_TYPE_FLOAT, 0, 72, offsetof(mavlink_sim_state_t, vn) }, \ - { "ve", NULL, MAVLINK_TYPE_FLOAT, 0, 76, offsetof(mavlink_sim_state_t, ve) }, \ - { "vd", NULL, MAVLINK_TYPE_FLOAT, 0, 80, offsetof(mavlink_sim_state_t, vd) }, \ - { "lat_int", NULL, MAVLINK_TYPE_INT32_T, 0, 84, offsetof(mavlink_sim_state_t, lat_int) }, \ - { "lon_int", NULL, MAVLINK_TYPE_INT32_T, 0, 88, offsetof(mavlink_sim_state_t, lon_int) }, \ - } \ -} -#endif - -/** - * @brief Pack a sim_state message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param q1 True attitude quaternion component 1, w (1 in null-rotation) - * @param q2 True attitude quaternion component 2, x (0 in null-rotation) - * @param q3 True attitude quaternion component 3, y (0 in null-rotation) - * @param q4 True attitude quaternion component 4, z (0 in null-rotation) - * @param roll Attitude roll expressed as Euler angles, not recommended except for human-readable outputs - * @param pitch Attitude pitch expressed as Euler angles, not recommended except for human-readable outputs - * @param yaw Attitude yaw expressed as Euler angles, not recommended except for human-readable outputs - * @param xacc [m/s/s] X acceleration - * @param yacc [m/s/s] Y acceleration - * @param zacc [m/s/s] Z acceleration - * @param xgyro [rad/s] Angular speed around X axis - * @param ygyro [rad/s] Angular speed around Y axis - * @param zgyro [rad/s] Angular speed around Z axis - * @param lat [deg] Latitude (lower precision). Both this and the lat_int field should be set. - * @param lon [deg] Longitude (lower precision). Both this and the lon_int field should be set. - * @param alt [m] Altitude - * @param std_dev_horz Horizontal position standard deviation - * @param std_dev_vert Vertical position standard deviation - * @param vn [m/s] True velocity in north direction in earth-fixed NED frame - * @param ve [m/s] True velocity in east direction in earth-fixed NED frame - * @param vd [m/s] True velocity in down direction in earth-fixed NED frame - * @param lat_int [degE7] Latitude (higher precision). If 0, recipients should use the lat field value (otherwise this field is preferred). - * @param lon_int [degE7] Longitude (higher precision). If 0, recipients should use the lon field value (otherwise this field is preferred). - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_sim_state_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - float q1, float q2, float q3, float q4, float roll, float pitch, float yaw, float xacc, float yacc, float zacc, float xgyro, float ygyro, float zgyro, float lat, float lon, float alt, float std_dev_horz, float std_dev_vert, float vn, float ve, float vd, int32_t lat_int, int32_t lon_int) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SIM_STATE_LEN]; - _mav_put_float(buf, 0, q1); - _mav_put_float(buf, 4, q2); - _mav_put_float(buf, 8, q3); - _mav_put_float(buf, 12, q4); - _mav_put_float(buf, 16, roll); - _mav_put_float(buf, 20, pitch); - _mav_put_float(buf, 24, yaw); - _mav_put_float(buf, 28, xacc); - _mav_put_float(buf, 32, yacc); - _mav_put_float(buf, 36, zacc); - _mav_put_float(buf, 40, xgyro); - _mav_put_float(buf, 44, ygyro); - _mav_put_float(buf, 48, zgyro); - _mav_put_float(buf, 52, lat); - _mav_put_float(buf, 56, lon); - _mav_put_float(buf, 60, alt); - _mav_put_float(buf, 64, std_dev_horz); - _mav_put_float(buf, 68, std_dev_vert); - _mav_put_float(buf, 72, vn); - _mav_put_float(buf, 76, ve); - _mav_put_float(buf, 80, vd); - _mav_put_int32_t(buf, 84, lat_int); - _mav_put_int32_t(buf, 88, lon_int); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SIM_STATE_LEN); -#else - mavlink_sim_state_t packet; - packet.q1 = q1; - packet.q2 = q2; - packet.q3 = q3; - packet.q4 = q4; - packet.roll = roll; - packet.pitch = pitch; - packet.yaw = yaw; - packet.xacc = xacc; - packet.yacc = yacc; - packet.zacc = zacc; - packet.xgyro = xgyro; - packet.ygyro = ygyro; - packet.zgyro = zgyro; - packet.lat = lat; - packet.lon = lon; - packet.alt = alt; - packet.std_dev_horz = std_dev_horz; - packet.std_dev_vert = std_dev_vert; - packet.vn = vn; - packet.ve = ve; - packet.vd = vd; - packet.lat_int = lat_int; - packet.lon_int = lon_int; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SIM_STATE_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SIM_STATE; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SIM_STATE_MIN_LEN, MAVLINK_MSG_ID_SIM_STATE_LEN, MAVLINK_MSG_ID_SIM_STATE_CRC); -} - -/** - * @brief Pack a sim_state message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param q1 True attitude quaternion component 1, w (1 in null-rotation) - * @param q2 True attitude quaternion component 2, x (0 in null-rotation) - * @param q3 True attitude quaternion component 3, y (0 in null-rotation) - * @param q4 True attitude quaternion component 4, z (0 in null-rotation) - * @param roll Attitude roll expressed as Euler angles, not recommended except for human-readable outputs - * @param pitch Attitude pitch expressed as Euler angles, not recommended except for human-readable outputs - * @param yaw Attitude yaw expressed as Euler angles, not recommended except for human-readable outputs - * @param xacc [m/s/s] X acceleration - * @param yacc [m/s/s] Y acceleration - * @param zacc [m/s/s] Z acceleration - * @param xgyro [rad/s] Angular speed around X axis - * @param ygyro [rad/s] Angular speed around Y axis - * @param zgyro [rad/s] Angular speed around Z axis - * @param lat [deg] Latitude (lower precision). Both this and the lat_int field should be set. - * @param lon [deg] Longitude (lower precision). Both this and the lon_int field should be set. - * @param alt [m] Altitude - * @param std_dev_horz Horizontal position standard deviation - * @param std_dev_vert Vertical position standard deviation - * @param vn [m/s] True velocity in north direction in earth-fixed NED frame - * @param ve [m/s] True velocity in east direction in earth-fixed NED frame - * @param vd [m/s] True velocity in down direction in earth-fixed NED frame - * @param lat_int [degE7] Latitude (higher precision). If 0, recipients should use the lat field value (otherwise this field is preferred). - * @param lon_int [degE7] Longitude (higher precision). If 0, recipients should use the lon field value (otherwise this field is preferred). - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_sim_state_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - float q1,float q2,float q3,float q4,float roll,float pitch,float yaw,float xacc,float yacc,float zacc,float xgyro,float ygyro,float zgyro,float lat,float lon,float alt,float std_dev_horz,float std_dev_vert,float vn,float ve,float vd,int32_t lat_int,int32_t lon_int) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SIM_STATE_LEN]; - _mav_put_float(buf, 0, q1); - _mav_put_float(buf, 4, q2); - _mav_put_float(buf, 8, q3); - _mav_put_float(buf, 12, q4); - _mav_put_float(buf, 16, roll); - _mav_put_float(buf, 20, pitch); - _mav_put_float(buf, 24, yaw); - _mav_put_float(buf, 28, xacc); - _mav_put_float(buf, 32, yacc); - _mav_put_float(buf, 36, zacc); - _mav_put_float(buf, 40, xgyro); - _mav_put_float(buf, 44, ygyro); - _mav_put_float(buf, 48, zgyro); - _mav_put_float(buf, 52, lat); - _mav_put_float(buf, 56, lon); - _mav_put_float(buf, 60, alt); - _mav_put_float(buf, 64, std_dev_horz); - _mav_put_float(buf, 68, std_dev_vert); - _mav_put_float(buf, 72, vn); - _mav_put_float(buf, 76, ve); - _mav_put_float(buf, 80, vd); - _mav_put_int32_t(buf, 84, lat_int); - _mav_put_int32_t(buf, 88, lon_int); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SIM_STATE_LEN); -#else - mavlink_sim_state_t packet; - packet.q1 = q1; - packet.q2 = q2; - packet.q3 = q3; - packet.q4 = q4; - packet.roll = roll; - packet.pitch = pitch; - packet.yaw = yaw; - packet.xacc = xacc; - packet.yacc = yacc; - packet.zacc = zacc; - packet.xgyro = xgyro; - packet.ygyro = ygyro; - packet.zgyro = zgyro; - packet.lat = lat; - packet.lon = lon; - packet.alt = alt; - packet.std_dev_horz = std_dev_horz; - packet.std_dev_vert = std_dev_vert; - packet.vn = vn; - packet.ve = ve; - packet.vd = vd; - packet.lat_int = lat_int; - packet.lon_int = lon_int; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SIM_STATE_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SIM_STATE; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SIM_STATE_MIN_LEN, MAVLINK_MSG_ID_SIM_STATE_LEN, MAVLINK_MSG_ID_SIM_STATE_CRC); -} - -/** - * @brief Encode a sim_state struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param sim_state C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_sim_state_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_sim_state_t* sim_state) -{ - return mavlink_msg_sim_state_pack(system_id, component_id, msg, sim_state->q1, sim_state->q2, sim_state->q3, sim_state->q4, sim_state->roll, sim_state->pitch, sim_state->yaw, sim_state->xacc, sim_state->yacc, sim_state->zacc, sim_state->xgyro, sim_state->ygyro, sim_state->zgyro, sim_state->lat, sim_state->lon, sim_state->alt, sim_state->std_dev_horz, sim_state->std_dev_vert, sim_state->vn, sim_state->ve, sim_state->vd, sim_state->lat_int, sim_state->lon_int); -} - -/** - * @brief Encode a sim_state struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param sim_state C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_sim_state_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_sim_state_t* sim_state) -{ - return mavlink_msg_sim_state_pack_chan(system_id, component_id, chan, msg, sim_state->q1, sim_state->q2, sim_state->q3, sim_state->q4, sim_state->roll, sim_state->pitch, sim_state->yaw, sim_state->xacc, sim_state->yacc, sim_state->zacc, sim_state->xgyro, sim_state->ygyro, sim_state->zgyro, sim_state->lat, sim_state->lon, sim_state->alt, sim_state->std_dev_horz, sim_state->std_dev_vert, sim_state->vn, sim_state->ve, sim_state->vd, sim_state->lat_int, sim_state->lon_int); -} - -/** - * @brief Send a sim_state message - * @param chan MAVLink channel to send the message - * - * @param q1 True attitude quaternion component 1, w (1 in null-rotation) - * @param q2 True attitude quaternion component 2, x (0 in null-rotation) - * @param q3 True attitude quaternion component 3, y (0 in null-rotation) - * @param q4 True attitude quaternion component 4, z (0 in null-rotation) - * @param roll Attitude roll expressed as Euler angles, not recommended except for human-readable outputs - * @param pitch Attitude pitch expressed as Euler angles, not recommended except for human-readable outputs - * @param yaw Attitude yaw expressed as Euler angles, not recommended except for human-readable outputs - * @param xacc [m/s/s] X acceleration - * @param yacc [m/s/s] Y acceleration - * @param zacc [m/s/s] Z acceleration - * @param xgyro [rad/s] Angular speed around X axis - * @param ygyro [rad/s] Angular speed around Y axis - * @param zgyro [rad/s] Angular speed around Z axis - * @param lat [deg] Latitude (lower precision). Both this and the lat_int field should be set. - * @param lon [deg] Longitude (lower precision). Both this and the lon_int field should be set. - * @param alt [m] Altitude - * @param std_dev_horz Horizontal position standard deviation - * @param std_dev_vert Vertical position standard deviation - * @param vn [m/s] True velocity in north direction in earth-fixed NED frame - * @param ve [m/s] True velocity in east direction in earth-fixed NED frame - * @param vd [m/s] True velocity in down direction in earth-fixed NED frame - * @param lat_int [degE7] Latitude (higher precision). If 0, recipients should use the lat field value (otherwise this field is preferred). - * @param lon_int [degE7] Longitude (higher precision). If 0, recipients should use the lon field value (otherwise this field is preferred). - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_sim_state_send(mavlink_channel_t chan, float q1, float q2, float q3, float q4, float roll, float pitch, float yaw, float xacc, float yacc, float zacc, float xgyro, float ygyro, float zgyro, float lat, float lon, float alt, float std_dev_horz, float std_dev_vert, float vn, float ve, float vd, int32_t lat_int, int32_t lon_int) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SIM_STATE_LEN]; - _mav_put_float(buf, 0, q1); - _mav_put_float(buf, 4, q2); - _mav_put_float(buf, 8, q3); - _mav_put_float(buf, 12, q4); - _mav_put_float(buf, 16, roll); - _mav_put_float(buf, 20, pitch); - _mav_put_float(buf, 24, yaw); - _mav_put_float(buf, 28, xacc); - _mav_put_float(buf, 32, yacc); - _mav_put_float(buf, 36, zacc); - _mav_put_float(buf, 40, xgyro); - _mav_put_float(buf, 44, ygyro); - _mav_put_float(buf, 48, zgyro); - _mav_put_float(buf, 52, lat); - _mav_put_float(buf, 56, lon); - _mav_put_float(buf, 60, alt); - _mav_put_float(buf, 64, std_dev_horz); - _mav_put_float(buf, 68, std_dev_vert); - _mav_put_float(buf, 72, vn); - _mav_put_float(buf, 76, ve); - _mav_put_float(buf, 80, vd); - _mav_put_int32_t(buf, 84, lat_int); - _mav_put_int32_t(buf, 88, lon_int); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SIM_STATE, buf, MAVLINK_MSG_ID_SIM_STATE_MIN_LEN, MAVLINK_MSG_ID_SIM_STATE_LEN, MAVLINK_MSG_ID_SIM_STATE_CRC); -#else - mavlink_sim_state_t packet; - packet.q1 = q1; - packet.q2 = q2; - packet.q3 = q3; - packet.q4 = q4; - packet.roll = roll; - packet.pitch = pitch; - packet.yaw = yaw; - packet.xacc = xacc; - packet.yacc = yacc; - packet.zacc = zacc; - packet.xgyro = xgyro; - packet.ygyro = ygyro; - packet.zgyro = zgyro; - packet.lat = lat; - packet.lon = lon; - packet.alt = alt; - packet.std_dev_horz = std_dev_horz; - packet.std_dev_vert = std_dev_vert; - packet.vn = vn; - packet.ve = ve; - packet.vd = vd; - packet.lat_int = lat_int; - packet.lon_int = lon_int; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SIM_STATE, (const char *)&packet, MAVLINK_MSG_ID_SIM_STATE_MIN_LEN, MAVLINK_MSG_ID_SIM_STATE_LEN, MAVLINK_MSG_ID_SIM_STATE_CRC); -#endif -} - -/** - * @brief Send a sim_state message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_sim_state_send_struct(mavlink_channel_t chan, const mavlink_sim_state_t* sim_state) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_sim_state_send(chan, sim_state->q1, sim_state->q2, sim_state->q3, sim_state->q4, sim_state->roll, sim_state->pitch, sim_state->yaw, sim_state->xacc, sim_state->yacc, sim_state->zacc, sim_state->xgyro, sim_state->ygyro, sim_state->zgyro, sim_state->lat, sim_state->lon, sim_state->alt, sim_state->std_dev_horz, sim_state->std_dev_vert, sim_state->vn, sim_state->ve, sim_state->vd, sim_state->lat_int, sim_state->lon_int); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SIM_STATE, (const char *)sim_state, MAVLINK_MSG_ID_SIM_STATE_MIN_LEN, MAVLINK_MSG_ID_SIM_STATE_LEN, MAVLINK_MSG_ID_SIM_STATE_CRC); -#endif -} - -#if MAVLINK_MSG_ID_SIM_STATE_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_sim_state_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, float q1, float q2, float q3, float q4, float roll, float pitch, float yaw, float xacc, float yacc, float zacc, float xgyro, float ygyro, float zgyro, float lat, float lon, float alt, float std_dev_horz, float std_dev_vert, float vn, float ve, float vd, int32_t lat_int, int32_t lon_int) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_float(buf, 0, q1); - _mav_put_float(buf, 4, q2); - _mav_put_float(buf, 8, q3); - _mav_put_float(buf, 12, q4); - _mav_put_float(buf, 16, roll); - _mav_put_float(buf, 20, pitch); - _mav_put_float(buf, 24, yaw); - _mav_put_float(buf, 28, xacc); - _mav_put_float(buf, 32, yacc); - _mav_put_float(buf, 36, zacc); - _mav_put_float(buf, 40, xgyro); - _mav_put_float(buf, 44, ygyro); - _mav_put_float(buf, 48, zgyro); - _mav_put_float(buf, 52, lat); - _mav_put_float(buf, 56, lon); - _mav_put_float(buf, 60, alt); - _mav_put_float(buf, 64, std_dev_horz); - _mav_put_float(buf, 68, std_dev_vert); - _mav_put_float(buf, 72, vn); - _mav_put_float(buf, 76, ve); - _mav_put_float(buf, 80, vd); - _mav_put_int32_t(buf, 84, lat_int); - _mav_put_int32_t(buf, 88, lon_int); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SIM_STATE, buf, MAVLINK_MSG_ID_SIM_STATE_MIN_LEN, MAVLINK_MSG_ID_SIM_STATE_LEN, MAVLINK_MSG_ID_SIM_STATE_CRC); -#else - mavlink_sim_state_t *packet = (mavlink_sim_state_t *)msgbuf; - packet->q1 = q1; - packet->q2 = q2; - packet->q3 = q3; - packet->q4 = q4; - packet->roll = roll; - packet->pitch = pitch; - packet->yaw = yaw; - packet->xacc = xacc; - packet->yacc = yacc; - packet->zacc = zacc; - packet->xgyro = xgyro; - packet->ygyro = ygyro; - packet->zgyro = zgyro; - packet->lat = lat; - packet->lon = lon; - packet->alt = alt; - packet->std_dev_horz = std_dev_horz; - packet->std_dev_vert = std_dev_vert; - packet->vn = vn; - packet->ve = ve; - packet->vd = vd; - packet->lat_int = lat_int; - packet->lon_int = lon_int; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SIM_STATE, (const char *)packet, MAVLINK_MSG_ID_SIM_STATE_MIN_LEN, MAVLINK_MSG_ID_SIM_STATE_LEN, MAVLINK_MSG_ID_SIM_STATE_CRC); -#endif -} -#endif - -#endif - -// MESSAGE SIM_STATE UNPACKING - - -/** - * @brief Get field q1 from sim_state message - * - * @return True attitude quaternion component 1, w (1 in null-rotation) - */ -static inline float mavlink_msg_sim_state_get_q1(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 0); -} - -/** - * @brief Get field q2 from sim_state message - * - * @return True attitude quaternion component 2, x (0 in null-rotation) - */ -static inline float mavlink_msg_sim_state_get_q2(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 4); -} - -/** - * @brief Get field q3 from sim_state message - * - * @return True attitude quaternion component 3, y (0 in null-rotation) - */ -static inline float mavlink_msg_sim_state_get_q3(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field q4 from sim_state message - * - * @return True attitude quaternion component 4, z (0 in null-rotation) - */ -static inline float mavlink_msg_sim_state_get_q4(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field roll from sim_state message - * - * @return Attitude roll expressed as Euler angles, not recommended except for human-readable outputs - */ -static inline float mavlink_msg_sim_state_get_roll(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field pitch from sim_state message - * - * @return Attitude pitch expressed as Euler angles, not recommended except for human-readable outputs - */ -static inline float mavlink_msg_sim_state_get_pitch(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Get field yaw from sim_state message - * - * @return Attitude yaw expressed as Euler angles, not recommended except for human-readable outputs - */ -static inline float mavlink_msg_sim_state_get_yaw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Get field xacc from sim_state message - * - * @return [m/s/s] X acceleration - */ -static inline float mavlink_msg_sim_state_get_xacc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 28); -} - -/** - * @brief Get field yacc from sim_state message - * - * @return [m/s/s] Y acceleration - */ -static inline float mavlink_msg_sim_state_get_yacc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 32); -} - -/** - * @brief Get field zacc from sim_state message - * - * @return [m/s/s] Z acceleration - */ -static inline float mavlink_msg_sim_state_get_zacc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 36); -} - -/** - * @brief Get field xgyro from sim_state message - * - * @return [rad/s] Angular speed around X axis - */ -static inline float mavlink_msg_sim_state_get_xgyro(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 40); -} - -/** - * @brief Get field ygyro from sim_state message - * - * @return [rad/s] Angular speed around Y axis - */ -static inline float mavlink_msg_sim_state_get_ygyro(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 44); -} - -/** - * @brief Get field zgyro from sim_state message - * - * @return [rad/s] Angular speed around Z axis - */ -static inline float mavlink_msg_sim_state_get_zgyro(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 48); -} - -/** - * @brief Get field lat from sim_state message - * - * @return [deg] Latitude (lower precision). Both this and the lat_int field should be set. - */ -static inline float mavlink_msg_sim_state_get_lat(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 52); -} - -/** - * @brief Get field lon from sim_state message - * - * @return [deg] Longitude (lower precision). Both this and the lon_int field should be set. - */ -static inline float mavlink_msg_sim_state_get_lon(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 56); -} - -/** - * @brief Get field alt from sim_state message - * - * @return [m] Altitude - */ -static inline float mavlink_msg_sim_state_get_alt(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 60); -} - -/** - * @brief Get field std_dev_horz from sim_state message - * - * @return Horizontal position standard deviation - */ -static inline float mavlink_msg_sim_state_get_std_dev_horz(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 64); -} - -/** - * @brief Get field std_dev_vert from sim_state message - * - * @return Vertical position standard deviation - */ -static inline float mavlink_msg_sim_state_get_std_dev_vert(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 68); -} - -/** - * @brief Get field vn from sim_state message - * - * @return [m/s] True velocity in north direction in earth-fixed NED frame - */ -static inline float mavlink_msg_sim_state_get_vn(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 72); -} - -/** - * @brief Get field ve from sim_state message - * - * @return [m/s] True velocity in east direction in earth-fixed NED frame - */ -static inline float mavlink_msg_sim_state_get_ve(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 76); -} - -/** - * @brief Get field vd from sim_state message - * - * @return [m/s] True velocity in down direction in earth-fixed NED frame - */ -static inline float mavlink_msg_sim_state_get_vd(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 80); -} - -/** - * @brief Get field lat_int from sim_state message - * - * @return [degE7] Latitude (higher precision). If 0, recipients should use the lat field value (otherwise this field is preferred). - */ -static inline int32_t mavlink_msg_sim_state_get_lat_int(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 84); -} - -/** - * @brief Get field lon_int from sim_state message - * - * @return [degE7] Longitude (higher precision). If 0, recipients should use the lon field value (otherwise this field is preferred). - */ -static inline int32_t mavlink_msg_sim_state_get_lon_int(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 88); -} - -/** - * @brief Decode a sim_state message into a struct - * - * @param msg The message to decode - * @param sim_state C-struct to decode the message contents into - */ -static inline void mavlink_msg_sim_state_decode(const mavlink_message_t* msg, mavlink_sim_state_t* sim_state) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - sim_state->q1 = mavlink_msg_sim_state_get_q1(msg); - sim_state->q2 = mavlink_msg_sim_state_get_q2(msg); - sim_state->q3 = mavlink_msg_sim_state_get_q3(msg); - sim_state->q4 = mavlink_msg_sim_state_get_q4(msg); - sim_state->roll = mavlink_msg_sim_state_get_roll(msg); - sim_state->pitch = mavlink_msg_sim_state_get_pitch(msg); - sim_state->yaw = mavlink_msg_sim_state_get_yaw(msg); - sim_state->xacc = mavlink_msg_sim_state_get_xacc(msg); - sim_state->yacc = mavlink_msg_sim_state_get_yacc(msg); - sim_state->zacc = mavlink_msg_sim_state_get_zacc(msg); - sim_state->xgyro = mavlink_msg_sim_state_get_xgyro(msg); - sim_state->ygyro = mavlink_msg_sim_state_get_ygyro(msg); - sim_state->zgyro = mavlink_msg_sim_state_get_zgyro(msg); - sim_state->lat = mavlink_msg_sim_state_get_lat(msg); - sim_state->lon = mavlink_msg_sim_state_get_lon(msg); - sim_state->alt = mavlink_msg_sim_state_get_alt(msg); - sim_state->std_dev_horz = mavlink_msg_sim_state_get_std_dev_horz(msg); - sim_state->std_dev_vert = mavlink_msg_sim_state_get_std_dev_vert(msg); - sim_state->vn = mavlink_msg_sim_state_get_vn(msg); - sim_state->ve = mavlink_msg_sim_state_get_ve(msg); - sim_state->vd = mavlink_msg_sim_state_get_vd(msg); - sim_state->lat_int = mavlink_msg_sim_state_get_lat_int(msg); - sim_state->lon_int = mavlink_msg_sim_state_get_lon_int(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_SIM_STATE_LEN? msg->len : MAVLINK_MSG_ID_SIM_STATE_LEN; - memset(sim_state, 0, MAVLINK_MSG_ID_SIM_STATE_LEN); - memcpy(sim_state, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_smart_battery_info.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_smart_battery_info.h deleted file mode 100644 index 6c09bbe8..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_smart_battery_info.h +++ /dev/null @@ -1,607 +0,0 @@ -#pragma once -// MESSAGE SMART_BATTERY_INFO PACKING - -#define MAVLINK_MSG_ID_SMART_BATTERY_INFO 370 - -MAVPACKED( -typedef struct __mavlink_smart_battery_info_t { - int32_t capacity_full_specification; /*< [mAh] Capacity when full according to manufacturer, -1: field not provided.*/ - int32_t capacity_full; /*< [mAh] Capacity when full (accounting for battery degradation), -1: field not provided.*/ - uint16_t cycle_count; /*< Charge/discharge cycle count. UINT16_MAX: field not provided.*/ - uint16_t weight; /*< [g] Battery weight. 0: field not provided.*/ - uint16_t discharge_minimum_voltage; /*< [mV] Minimum per-cell voltage when discharging. If not supplied set to UINT16_MAX value.*/ - uint16_t charging_minimum_voltage; /*< [mV] Minimum per-cell voltage when charging. If not supplied set to UINT16_MAX value.*/ - uint16_t resting_minimum_voltage; /*< [mV] Minimum per-cell voltage when resting. If not supplied set to UINT16_MAX value.*/ - uint8_t id; /*< Battery ID*/ - uint8_t battery_function; /*< Function of the battery*/ - uint8_t type; /*< Type (chemistry) of the battery*/ - char serial_number[16]; /*< Serial number in ASCII characters, 0 terminated. All 0: field not provided.*/ - char device_name[50]; /*< Static device name in ASCII characters, 0 terminated. All 0: field not provided. Encode as manufacturer name then product name separated using an underscore.*/ - uint16_t charging_maximum_voltage; /*< [mV] Maximum per-cell voltage when charged. 0: field not provided.*/ - uint8_t cells_in_series; /*< Number of battery cells in series. 0: field not provided.*/ - uint32_t discharge_maximum_current; /*< [mA] Maximum pack discharge current. 0: field not provided.*/ - uint32_t discharge_maximum_burst_current; /*< [mA] Maximum pack discharge burst current. 0: field not provided.*/ - char manufacture_date[11]; /*< Manufacture date (DD/MM/YYYY) in ASCII characters, 0 terminated. All 0: field not provided.*/ -}) mavlink_smart_battery_info_t; - -#define MAVLINK_MSG_ID_SMART_BATTERY_INFO_LEN 109 -#define MAVLINK_MSG_ID_SMART_BATTERY_INFO_MIN_LEN 87 -#define MAVLINK_MSG_ID_370_LEN 109 -#define MAVLINK_MSG_ID_370_MIN_LEN 87 - -#define MAVLINK_MSG_ID_SMART_BATTERY_INFO_CRC 75 -#define MAVLINK_MSG_ID_370_CRC 75 - -#define MAVLINK_MSG_SMART_BATTERY_INFO_FIELD_SERIAL_NUMBER_LEN 16 -#define MAVLINK_MSG_SMART_BATTERY_INFO_FIELD_DEVICE_NAME_LEN 50 -#define MAVLINK_MSG_SMART_BATTERY_INFO_FIELD_MANUFACTURE_DATE_LEN 11 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_SMART_BATTERY_INFO { \ - 370, \ - "SMART_BATTERY_INFO", \ - 17, \ - { { "id", NULL, MAVLINK_TYPE_UINT8_T, 0, 18, offsetof(mavlink_smart_battery_info_t, id) }, \ - { "battery_function", NULL, MAVLINK_TYPE_UINT8_T, 0, 19, offsetof(mavlink_smart_battery_info_t, battery_function) }, \ - { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_smart_battery_info_t, type) }, \ - { "capacity_full_specification", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_smart_battery_info_t, capacity_full_specification) }, \ - { "capacity_full", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_smart_battery_info_t, capacity_full) }, \ - { "cycle_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_smart_battery_info_t, cycle_count) }, \ - { "serial_number", NULL, MAVLINK_TYPE_CHAR, 16, 21, offsetof(mavlink_smart_battery_info_t, serial_number) }, \ - { "device_name", NULL, MAVLINK_TYPE_CHAR, 50, 37, offsetof(mavlink_smart_battery_info_t, device_name) }, \ - { "weight", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_smart_battery_info_t, weight) }, \ - { "discharge_minimum_voltage", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_smart_battery_info_t, discharge_minimum_voltage) }, \ - { "charging_minimum_voltage", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_smart_battery_info_t, charging_minimum_voltage) }, \ - { "resting_minimum_voltage", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_smart_battery_info_t, resting_minimum_voltage) }, \ - { "charging_maximum_voltage", NULL, MAVLINK_TYPE_UINT16_T, 0, 87, offsetof(mavlink_smart_battery_info_t, charging_maximum_voltage) }, \ - { "cells_in_series", NULL, MAVLINK_TYPE_UINT8_T, 0, 89, offsetof(mavlink_smart_battery_info_t, cells_in_series) }, \ - { "discharge_maximum_current", NULL, MAVLINK_TYPE_UINT32_T, 0, 90, offsetof(mavlink_smart_battery_info_t, discharge_maximum_current) }, \ - { "discharge_maximum_burst_current", NULL, MAVLINK_TYPE_UINT32_T, 0, 94, offsetof(mavlink_smart_battery_info_t, discharge_maximum_burst_current) }, \ - { "manufacture_date", NULL, MAVLINK_TYPE_CHAR, 11, 98, offsetof(mavlink_smart_battery_info_t, manufacture_date) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_SMART_BATTERY_INFO { \ - "SMART_BATTERY_INFO", \ - 17, \ - { { "id", NULL, MAVLINK_TYPE_UINT8_T, 0, 18, offsetof(mavlink_smart_battery_info_t, id) }, \ - { "battery_function", NULL, MAVLINK_TYPE_UINT8_T, 0, 19, offsetof(mavlink_smart_battery_info_t, battery_function) }, \ - { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_smart_battery_info_t, type) }, \ - { "capacity_full_specification", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_smart_battery_info_t, capacity_full_specification) }, \ - { "capacity_full", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_smart_battery_info_t, capacity_full) }, \ - { "cycle_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_smart_battery_info_t, cycle_count) }, \ - { "serial_number", NULL, MAVLINK_TYPE_CHAR, 16, 21, offsetof(mavlink_smart_battery_info_t, serial_number) }, \ - { "device_name", NULL, MAVLINK_TYPE_CHAR, 50, 37, offsetof(mavlink_smart_battery_info_t, device_name) }, \ - { "weight", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_smart_battery_info_t, weight) }, \ - { "discharge_minimum_voltage", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_smart_battery_info_t, discharge_minimum_voltage) }, \ - { "charging_minimum_voltage", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_smart_battery_info_t, charging_minimum_voltage) }, \ - { "resting_minimum_voltage", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_smart_battery_info_t, resting_minimum_voltage) }, \ - { "charging_maximum_voltage", NULL, MAVLINK_TYPE_UINT16_T, 0, 87, offsetof(mavlink_smart_battery_info_t, charging_maximum_voltage) }, \ - { "cells_in_series", NULL, MAVLINK_TYPE_UINT8_T, 0, 89, offsetof(mavlink_smart_battery_info_t, cells_in_series) }, \ - { "discharge_maximum_current", NULL, MAVLINK_TYPE_UINT32_T, 0, 90, offsetof(mavlink_smart_battery_info_t, discharge_maximum_current) }, \ - { "discharge_maximum_burst_current", NULL, MAVLINK_TYPE_UINT32_T, 0, 94, offsetof(mavlink_smart_battery_info_t, discharge_maximum_burst_current) }, \ - { "manufacture_date", NULL, MAVLINK_TYPE_CHAR, 11, 98, offsetof(mavlink_smart_battery_info_t, manufacture_date) }, \ - } \ -} -#endif - -/** - * @brief Pack a smart_battery_info message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param id Battery ID - * @param battery_function Function of the battery - * @param type Type (chemistry) of the battery - * @param capacity_full_specification [mAh] Capacity when full according to manufacturer, -1: field not provided. - * @param capacity_full [mAh] Capacity when full (accounting for battery degradation), -1: field not provided. - * @param cycle_count Charge/discharge cycle count. UINT16_MAX: field not provided. - * @param serial_number Serial number in ASCII characters, 0 terminated. All 0: field not provided. - * @param device_name Static device name in ASCII characters, 0 terminated. All 0: field not provided. Encode as manufacturer name then product name separated using an underscore. - * @param weight [g] Battery weight. 0: field not provided. - * @param discharge_minimum_voltage [mV] Minimum per-cell voltage when discharging. If not supplied set to UINT16_MAX value. - * @param charging_minimum_voltage [mV] Minimum per-cell voltage when charging. If not supplied set to UINT16_MAX value. - * @param resting_minimum_voltage [mV] Minimum per-cell voltage when resting. If not supplied set to UINT16_MAX value. - * @param charging_maximum_voltage [mV] Maximum per-cell voltage when charged. 0: field not provided. - * @param cells_in_series Number of battery cells in series. 0: field not provided. - * @param discharge_maximum_current [mA] Maximum pack discharge current. 0: field not provided. - * @param discharge_maximum_burst_current [mA] Maximum pack discharge burst current. 0: field not provided. - * @param manufacture_date Manufacture date (DD/MM/YYYY) in ASCII characters, 0 terminated. All 0: field not provided. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_smart_battery_info_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t id, uint8_t battery_function, uint8_t type, int32_t capacity_full_specification, int32_t capacity_full, uint16_t cycle_count, const char *serial_number, const char *device_name, uint16_t weight, uint16_t discharge_minimum_voltage, uint16_t charging_minimum_voltage, uint16_t resting_minimum_voltage, uint16_t charging_maximum_voltage, uint8_t cells_in_series, uint32_t discharge_maximum_current, uint32_t discharge_maximum_burst_current, const char *manufacture_date) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SMART_BATTERY_INFO_LEN]; - _mav_put_int32_t(buf, 0, capacity_full_specification); - _mav_put_int32_t(buf, 4, capacity_full); - _mav_put_uint16_t(buf, 8, cycle_count); - _mav_put_uint16_t(buf, 10, weight); - _mav_put_uint16_t(buf, 12, discharge_minimum_voltage); - _mav_put_uint16_t(buf, 14, charging_minimum_voltage); - _mav_put_uint16_t(buf, 16, resting_minimum_voltage); - _mav_put_uint8_t(buf, 18, id); - _mav_put_uint8_t(buf, 19, battery_function); - _mav_put_uint8_t(buf, 20, type); - _mav_put_uint16_t(buf, 87, charging_maximum_voltage); - _mav_put_uint8_t(buf, 89, cells_in_series); - _mav_put_uint32_t(buf, 90, discharge_maximum_current); - _mav_put_uint32_t(buf, 94, discharge_maximum_burst_current); - _mav_put_char_array(buf, 21, serial_number, 16); - _mav_put_char_array(buf, 37, device_name, 50); - _mav_put_char_array(buf, 98, manufacture_date, 11); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SMART_BATTERY_INFO_LEN); -#else - mavlink_smart_battery_info_t packet; - packet.capacity_full_specification = capacity_full_specification; - packet.capacity_full = capacity_full; - packet.cycle_count = cycle_count; - packet.weight = weight; - packet.discharge_minimum_voltage = discharge_minimum_voltage; - packet.charging_minimum_voltage = charging_minimum_voltage; - packet.resting_minimum_voltage = resting_minimum_voltage; - packet.id = id; - packet.battery_function = battery_function; - packet.type = type; - packet.charging_maximum_voltage = charging_maximum_voltage; - packet.cells_in_series = cells_in_series; - packet.discharge_maximum_current = discharge_maximum_current; - packet.discharge_maximum_burst_current = discharge_maximum_burst_current; - mav_array_memcpy(packet.serial_number, serial_number, sizeof(char)*16); - mav_array_memcpy(packet.device_name, device_name, sizeof(char)*50); - mav_array_memcpy(packet.manufacture_date, manufacture_date, sizeof(char)*11); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SMART_BATTERY_INFO_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SMART_BATTERY_INFO; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SMART_BATTERY_INFO_MIN_LEN, MAVLINK_MSG_ID_SMART_BATTERY_INFO_LEN, MAVLINK_MSG_ID_SMART_BATTERY_INFO_CRC); -} - -/** - * @brief Pack a smart_battery_info message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param id Battery ID - * @param battery_function Function of the battery - * @param type Type (chemistry) of the battery - * @param capacity_full_specification [mAh] Capacity when full according to manufacturer, -1: field not provided. - * @param capacity_full [mAh] Capacity when full (accounting for battery degradation), -1: field not provided. - * @param cycle_count Charge/discharge cycle count. UINT16_MAX: field not provided. - * @param serial_number Serial number in ASCII characters, 0 terminated. All 0: field not provided. - * @param device_name Static device name in ASCII characters, 0 terminated. All 0: field not provided. Encode as manufacturer name then product name separated using an underscore. - * @param weight [g] Battery weight. 0: field not provided. - * @param discharge_minimum_voltage [mV] Minimum per-cell voltage when discharging. If not supplied set to UINT16_MAX value. - * @param charging_minimum_voltage [mV] Minimum per-cell voltage when charging. If not supplied set to UINT16_MAX value. - * @param resting_minimum_voltage [mV] Minimum per-cell voltage when resting. If not supplied set to UINT16_MAX value. - * @param charging_maximum_voltage [mV] Maximum per-cell voltage when charged. 0: field not provided. - * @param cells_in_series Number of battery cells in series. 0: field not provided. - * @param discharge_maximum_current [mA] Maximum pack discharge current. 0: field not provided. - * @param discharge_maximum_burst_current [mA] Maximum pack discharge burst current. 0: field not provided. - * @param manufacture_date Manufacture date (DD/MM/YYYY) in ASCII characters, 0 terminated. All 0: field not provided. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_smart_battery_info_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t id,uint8_t battery_function,uint8_t type,int32_t capacity_full_specification,int32_t capacity_full,uint16_t cycle_count,const char *serial_number,const char *device_name,uint16_t weight,uint16_t discharge_minimum_voltage,uint16_t charging_minimum_voltage,uint16_t resting_minimum_voltage,uint16_t charging_maximum_voltage,uint8_t cells_in_series,uint32_t discharge_maximum_current,uint32_t discharge_maximum_burst_current,const char *manufacture_date) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SMART_BATTERY_INFO_LEN]; - _mav_put_int32_t(buf, 0, capacity_full_specification); - _mav_put_int32_t(buf, 4, capacity_full); - _mav_put_uint16_t(buf, 8, cycle_count); - _mav_put_uint16_t(buf, 10, weight); - _mav_put_uint16_t(buf, 12, discharge_minimum_voltage); - _mav_put_uint16_t(buf, 14, charging_minimum_voltage); - _mav_put_uint16_t(buf, 16, resting_minimum_voltage); - _mav_put_uint8_t(buf, 18, id); - _mav_put_uint8_t(buf, 19, battery_function); - _mav_put_uint8_t(buf, 20, type); - _mav_put_uint16_t(buf, 87, charging_maximum_voltage); - _mav_put_uint8_t(buf, 89, cells_in_series); - _mav_put_uint32_t(buf, 90, discharge_maximum_current); - _mav_put_uint32_t(buf, 94, discharge_maximum_burst_current); - _mav_put_char_array(buf, 21, serial_number, 16); - _mav_put_char_array(buf, 37, device_name, 50); - _mav_put_char_array(buf, 98, manufacture_date, 11); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SMART_BATTERY_INFO_LEN); -#else - mavlink_smart_battery_info_t packet; - packet.capacity_full_specification = capacity_full_specification; - packet.capacity_full = capacity_full; - packet.cycle_count = cycle_count; - packet.weight = weight; - packet.discharge_minimum_voltage = discharge_minimum_voltage; - packet.charging_minimum_voltage = charging_minimum_voltage; - packet.resting_minimum_voltage = resting_minimum_voltage; - packet.id = id; - packet.battery_function = battery_function; - packet.type = type; - packet.charging_maximum_voltage = charging_maximum_voltage; - packet.cells_in_series = cells_in_series; - packet.discharge_maximum_current = discharge_maximum_current; - packet.discharge_maximum_burst_current = discharge_maximum_burst_current; - mav_array_memcpy(packet.serial_number, serial_number, sizeof(char)*16); - mav_array_memcpy(packet.device_name, device_name, sizeof(char)*50); - mav_array_memcpy(packet.manufacture_date, manufacture_date, sizeof(char)*11); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SMART_BATTERY_INFO_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SMART_BATTERY_INFO; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SMART_BATTERY_INFO_MIN_LEN, MAVLINK_MSG_ID_SMART_BATTERY_INFO_LEN, MAVLINK_MSG_ID_SMART_BATTERY_INFO_CRC); -} - -/** - * @brief Encode a smart_battery_info struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param smart_battery_info C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_smart_battery_info_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_smart_battery_info_t* smart_battery_info) -{ - return mavlink_msg_smart_battery_info_pack(system_id, component_id, msg, smart_battery_info->id, smart_battery_info->battery_function, smart_battery_info->type, smart_battery_info->capacity_full_specification, smart_battery_info->capacity_full, smart_battery_info->cycle_count, smart_battery_info->serial_number, smart_battery_info->device_name, smart_battery_info->weight, smart_battery_info->discharge_minimum_voltage, smart_battery_info->charging_minimum_voltage, smart_battery_info->resting_minimum_voltage, smart_battery_info->charging_maximum_voltage, smart_battery_info->cells_in_series, smart_battery_info->discharge_maximum_current, smart_battery_info->discharge_maximum_burst_current, smart_battery_info->manufacture_date); -} - -/** - * @brief Encode a smart_battery_info struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param smart_battery_info C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_smart_battery_info_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_smart_battery_info_t* smart_battery_info) -{ - return mavlink_msg_smart_battery_info_pack_chan(system_id, component_id, chan, msg, smart_battery_info->id, smart_battery_info->battery_function, smart_battery_info->type, smart_battery_info->capacity_full_specification, smart_battery_info->capacity_full, smart_battery_info->cycle_count, smart_battery_info->serial_number, smart_battery_info->device_name, smart_battery_info->weight, smart_battery_info->discharge_minimum_voltage, smart_battery_info->charging_minimum_voltage, smart_battery_info->resting_minimum_voltage, smart_battery_info->charging_maximum_voltage, smart_battery_info->cells_in_series, smart_battery_info->discharge_maximum_current, smart_battery_info->discharge_maximum_burst_current, smart_battery_info->manufacture_date); -} - -/** - * @brief Send a smart_battery_info message - * @param chan MAVLink channel to send the message - * - * @param id Battery ID - * @param battery_function Function of the battery - * @param type Type (chemistry) of the battery - * @param capacity_full_specification [mAh] Capacity when full according to manufacturer, -1: field not provided. - * @param capacity_full [mAh] Capacity when full (accounting for battery degradation), -1: field not provided. - * @param cycle_count Charge/discharge cycle count. UINT16_MAX: field not provided. - * @param serial_number Serial number in ASCII characters, 0 terminated. All 0: field not provided. - * @param device_name Static device name in ASCII characters, 0 terminated. All 0: field not provided. Encode as manufacturer name then product name separated using an underscore. - * @param weight [g] Battery weight. 0: field not provided. - * @param discharge_minimum_voltage [mV] Minimum per-cell voltage when discharging. If not supplied set to UINT16_MAX value. - * @param charging_minimum_voltage [mV] Minimum per-cell voltage when charging. If not supplied set to UINT16_MAX value. - * @param resting_minimum_voltage [mV] Minimum per-cell voltage when resting. If not supplied set to UINT16_MAX value. - * @param charging_maximum_voltage [mV] Maximum per-cell voltage when charged. 0: field not provided. - * @param cells_in_series Number of battery cells in series. 0: field not provided. - * @param discharge_maximum_current [mA] Maximum pack discharge current. 0: field not provided. - * @param discharge_maximum_burst_current [mA] Maximum pack discharge burst current. 0: field not provided. - * @param manufacture_date Manufacture date (DD/MM/YYYY) in ASCII characters, 0 terminated. All 0: field not provided. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_smart_battery_info_send(mavlink_channel_t chan, uint8_t id, uint8_t battery_function, uint8_t type, int32_t capacity_full_specification, int32_t capacity_full, uint16_t cycle_count, const char *serial_number, const char *device_name, uint16_t weight, uint16_t discharge_minimum_voltage, uint16_t charging_minimum_voltage, uint16_t resting_minimum_voltage, uint16_t charging_maximum_voltage, uint8_t cells_in_series, uint32_t discharge_maximum_current, uint32_t discharge_maximum_burst_current, const char *manufacture_date) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SMART_BATTERY_INFO_LEN]; - _mav_put_int32_t(buf, 0, capacity_full_specification); - _mav_put_int32_t(buf, 4, capacity_full); - _mav_put_uint16_t(buf, 8, cycle_count); - _mav_put_uint16_t(buf, 10, weight); - _mav_put_uint16_t(buf, 12, discharge_minimum_voltage); - _mav_put_uint16_t(buf, 14, charging_minimum_voltage); - _mav_put_uint16_t(buf, 16, resting_minimum_voltage); - _mav_put_uint8_t(buf, 18, id); - _mav_put_uint8_t(buf, 19, battery_function); - _mav_put_uint8_t(buf, 20, type); - _mav_put_uint16_t(buf, 87, charging_maximum_voltage); - _mav_put_uint8_t(buf, 89, cells_in_series); - _mav_put_uint32_t(buf, 90, discharge_maximum_current); - _mav_put_uint32_t(buf, 94, discharge_maximum_burst_current); - _mav_put_char_array(buf, 21, serial_number, 16); - _mav_put_char_array(buf, 37, device_name, 50); - _mav_put_char_array(buf, 98, manufacture_date, 11); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SMART_BATTERY_INFO, buf, MAVLINK_MSG_ID_SMART_BATTERY_INFO_MIN_LEN, MAVLINK_MSG_ID_SMART_BATTERY_INFO_LEN, MAVLINK_MSG_ID_SMART_BATTERY_INFO_CRC); -#else - mavlink_smart_battery_info_t packet; - packet.capacity_full_specification = capacity_full_specification; - packet.capacity_full = capacity_full; - packet.cycle_count = cycle_count; - packet.weight = weight; - packet.discharge_minimum_voltage = discharge_minimum_voltage; - packet.charging_minimum_voltage = charging_minimum_voltage; - packet.resting_minimum_voltage = resting_minimum_voltage; - packet.id = id; - packet.battery_function = battery_function; - packet.type = type; - packet.charging_maximum_voltage = charging_maximum_voltage; - packet.cells_in_series = cells_in_series; - packet.discharge_maximum_current = discharge_maximum_current; - packet.discharge_maximum_burst_current = discharge_maximum_burst_current; - mav_array_memcpy(packet.serial_number, serial_number, sizeof(char)*16); - mav_array_memcpy(packet.device_name, device_name, sizeof(char)*50); - mav_array_memcpy(packet.manufacture_date, manufacture_date, sizeof(char)*11); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SMART_BATTERY_INFO, (const char *)&packet, MAVLINK_MSG_ID_SMART_BATTERY_INFO_MIN_LEN, MAVLINK_MSG_ID_SMART_BATTERY_INFO_LEN, MAVLINK_MSG_ID_SMART_BATTERY_INFO_CRC); -#endif -} - -/** - * @brief Send a smart_battery_info message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_smart_battery_info_send_struct(mavlink_channel_t chan, const mavlink_smart_battery_info_t* smart_battery_info) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_smart_battery_info_send(chan, smart_battery_info->id, smart_battery_info->battery_function, smart_battery_info->type, smart_battery_info->capacity_full_specification, smart_battery_info->capacity_full, smart_battery_info->cycle_count, smart_battery_info->serial_number, smart_battery_info->device_name, smart_battery_info->weight, smart_battery_info->discharge_minimum_voltage, smart_battery_info->charging_minimum_voltage, smart_battery_info->resting_minimum_voltage, smart_battery_info->charging_maximum_voltage, smart_battery_info->cells_in_series, smart_battery_info->discharge_maximum_current, smart_battery_info->discharge_maximum_burst_current, smart_battery_info->manufacture_date); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SMART_BATTERY_INFO, (const char *)smart_battery_info, MAVLINK_MSG_ID_SMART_BATTERY_INFO_MIN_LEN, MAVLINK_MSG_ID_SMART_BATTERY_INFO_LEN, MAVLINK_MSG_ID_SMART_BATTERY_INFO_CRC); -#endif -} - -#if MAVLINK_MSG_ID_SMART_BATTERY_INFO_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_smart_battery_info_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t id, uint8_t battery_function, uint8_t type, int32_t capacity_full_specification, int32_t capacity_full, uint16_t cycle_count, const char *serial_number, const char *device_name, uint16_t weight, uint16_t discharge_minimum_voltage, uint16_t charging_minimum_voltage, uint16_t resting_minimum_voltage, uint16_t charging_maximum_voltage, uint8_t cells_in_series, uint32_t discharge_maximum_current, uint32_t discharge_maximum_burst_current, const char *manufacture_date) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_int32_t(buf, 0, capacity_full_specification); - _mav_put_int32_t(buf, 4, capacity_full); - _mav_put_uint16_t(buf, 8, cycle_count); - _mav_put_uint16_t(buf, 10, weight); - _mav_put_uint16_t(buf, 12, discharge_minimum_voltage); - _mav_put_uint16_t(buf, 14, charging_minimum_voltage); - _mav_put_uint16_t(buf, 16, resting_minimum_voltage); - _mav_put_uint8_t(buf, 18, id); - _mav_put_uint8_t(buf, 19, battery_function); - _mav_put_uint8_t(buf, 20, type); - _mav_put_uint16_t(buf, 87, charging_maximum_voltage); - _mav_put_uint8_t(buf, 89, cells_in_series); - _mav_put_uint32_t(buf, 90, discharge_maximum_current); - _mav_put_uint32_t(buf, 94, discharge_maximum_burst_current); - _mav_put_char_array(buf, 21, serial_number, 16); - _mav_put_char_array(buf, 37, device_name, 50); - _mav_put_char_array(buf, 98, manufacture_date, 11); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SMART_BATTERY_INFO, buf, MAVLINK_MSG_ID_SMART_BATTERY_INFO_MIN_LEN, MAVLINK_MSG_ID_SMART_BATTERY_INFO_LEN, MAVLINK_MSG_ID_SMART_BATTERY_INFO_CRC); -#else - mavlink_smart_battery_info_t *packet = (mavlink_smart_battery_info_t *)msgbuf; - packet->capacity_full_specification = capacity_full_specification; - packet->capacity_full = capacity_full; - packet->cycle_count = cycle_count; - packet->weight = weight; - packet->discharge_minimum_voltage = discharge_minimum_voltage; - packet->charging_minimum_voltage = charging_minimum_voltage; - packet->resting_minimum_voltage = resting_minimum_voltage; - packet->id = id; - packet->battery_function = battery_function; - packet->type = type; - packet->charging_maximum_voltage = charging_maximum_voltage; - packet->cells_in_series = cells_in_series; - packet->discharge_maximum_current = discharge_maximum_current; - packet->discharge_maximum_burst_current = discharge_maximum_burst_current; - mav_array_memcpy(packet->serial_number, serial_number, sizeof(char)*16); - mav_array_memcpy(packet->device_name, device_name, sizeof(char)*50); - mav_array_memcpy(packet->manufacture_date, manufacture_date, sizeof(char)*11); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SMART_BATTERY_INFO, (const char *)packet, MAVLINK_MSG_ID_SMART_BATTERY_INFO_MIN_LEN, MAVLINK_MSG_ID_SMART_BATTERY_INFO_LEN, MAVLINK_MSG_ID_SMART_BATTERY_INFO_CRC); -#endif -} -#endif - -#endif - -// MESSAGE SMART_BATTERY_INFO UNPACKING - - -/** - * @brief Get field id from smart_battery_info message - * - * @return Battery ID - */ -static inline uint8_t mavlink_msg_smart_battery_info_get_id(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 18); -} - -/** - * @brief Get field battery_function from smart_battery_info message - * - * @return Function of the battery - */ -static inline uint8_t mavlink_msg_smart_battery_info_get_battery_function(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 19); -} - -/** - * @brief Get field type from smart_battery_info message - * - * @return Type (chemistry) of the battery - */ -static inline uint8_t mavlink_msg_smart_battery_info_get_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 20); -} - -/** - * @brief Get field capacity_full_specification from smart_battery_info message - * - * @return [mAh] Capacity when full according to manufacturer, -1: field not provided. - */ -static inline int32_t mavlink_msg_smart_battery_info_get_capacity_full_specification(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 0); -} - -/** - * @brief Get field capacity_full from smart_battery_info message - * - * @return [mAh] Capacity when full (accounting for battery degradation), -1: field not provided. - */ -static inline int32_t mavlink_msg_smart_battery_info_get_capacity_full(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 4); -} - -/** - * @brief Get field cycle_count from smart_battery_info message - * - * @return Charge/discharge cycle count. UINT16_MAX: field not provided. - */ -static inline uint16_t mavlink_msg_smart_battery_info_get_cycle_count(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 8); -} - -/** - * @brief Get field serial_number from smart_battery_info message - * - * @return Serial number in ASCII characters, 0 terminated. All 0: field not provided. - */ -static inline uint16_t mavlink_msg_smart_battery_info_get_serial_number(const mavlink_message_t* msg, char *serial_number) -{ - return _MAV_RETURN_char_array(msg, serial_number, 16, 21); -} - -/** - * @brief Get field device_name from smart_battery_info message - * - * @return Static device name in ASCII characters, 0 terminated. All 0: field not provided. Encode as manufacturer name then product name separated using an underscore. - */ -static inline uint16_t mavlink_msg_smart_battery_info_get_device_name(const mavlink_message_t* msg, char *device_name) -{ - return _MAV_RETURN_char_array(msg, device_name, 50, 37); -} - -/** - * @brief Get field weight from smart_battery_info message - * - * @return [g] Battery weight. 0: field not provided. - */ -static inline uint16_t mavlink_msg_smart_battery_info_get_weight(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 10); -} - -/** - * @brief Get field discharge_minimum_voltage from smart_battery_info message - * - * @return [mV] Minimum per-cell voltage when discharging. If not supplied set to UINT16_MAX value. - */ -static inline uint16_t mavlink_msg_smart_battery_info_get_discharge_minimum_voltage(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 12); -} - -/** - * @brief Get field charging_minimum_voltage from smart_battery_info message - * - * @return [mV] Minimum per-cell voltage when charging. If not supplied set to UINT16_MAX value. - */ -static inline uint16_t mavlink_msg_smart_battery_info_get_charging_minimum_voltage(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 14); -} - -/** - * @brief Get field resting_minimum_voltage from smart_battery_info message - * - * @return [mV] Minimum per-cell voltage when resting. If not supplied set to UINT16_MAX value. - */ -static inline uint16_t mavlink_msg_smart_battery_info_get_resting_minimum_voltage(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 16); -} - -/** - * @brief Get field charging_maximum_voltage from smart_battery_info message - * - * @return [mV] Maximum per-cell voltage when charged. 0: field not provided. - */ -static inline uint16_t mavlink_msg_smart_battery_info_get_charging_maximum_voltage(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 87); -} - -/** - * @brief Get field cells_in_series from smart_battery_info message - * - * @return Number of battery cells in series. 0: field not provided. - */ -static inline uint8_t mavlink_msg_smart_battery_info_get_cells_in_series(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 89); -} - -/** - * @brief Get field discharge_maximum_current from smart_battery_info message - * - * @return [mA] Maximum pack discharge current. 0: field not provided. - */ -static inline uint32_t mavlink_msg_smart_battery_info_get_discharge_maximum_current(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 90); -} - -/** - * @brief Get field discharge_maximum_burst_current from smart_battery_info message - * - * @return [mA] Maximum pack discharge burst current. 0: field not provided. - */ -static inline uint32_t mavlink_msg_smart_battery_info_get_discharge_maximum_burst_current(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 94); -} - -/** - * @brief Get field manufacture_date from smart_battery_info message - * - * @return Manufacture date (DD/MM/YYYY) in ASCII characters, 0 terminated. All 0: field not provided. - */ -static inline uint16_t mavlink_msg_smart_battery_info_get_manufacture_date(const mavlink_message_t* msg, char *manufacture_date) -{ - return _MAV_RETURN_char_array(msg, manufacture_date, 11, 98); -} - -/** - * @brief Decode a smart_battery_info message into a struct - * - * @param msg The message to decode - * @param smart_battery_info C-struct to decode the message contents into - */ -static inline void mavlink_msg_smart_battery_info_decode(const mavlink_message_t* msg, mavlink_smart_battery_info_t* smart_battery_info) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - smart_battery_info->capacity_full_specification = mavlink_msg_smart_battery_info_get_capacity_full_specification(msg); - smart_battery_info->capacity_full = mavlink_msg_smart_battery_info_get_capacity_full(msg); - smart_battery_info->cycle_count = mavlink_msg_smart_battery_info_get_cycle_count(msg); - smart_battery_info->weight = mavlink_msg_smart_battery_info_get_weight(msg); - smart_battery_info->discharge_minimum_voltage = mavlink_msg_smart_battery_info_get_discharge_minimum_voltage(msg); - smart_battery_info->charging_minimum_voltage = mavlink_msg_smart_battery_info_get_charging_minimum_voltage(msg); - smart_battery_info->resting_minimum_voltage = mavlink_msg_smart_battery_info_get_resting_minimum_voltage(msg); - smart_battery_info->id = mavlink_msg_smart_battery_info_get_id(msg); - smart_battery_info->battery_function = mavlink_msg_smart_battery_info_get_battery_function(msg); - smart_battery_info->type = mavlink_msg_smart_battery_info_get_type(msg); - mavlink_msg_smart_battery_info_get_serial_number(msg, smart_battery_info->serial_number); - mavlink_msg_smart_battery_info_get_device_name(msg, smart_battery_info->device_name); - smart_battery_info->charging_maximum_voltage = mavlink_msg_smart_battery_info_get_charging_maximum_voltage(msg); - smart_battery_info->cells_in_series = mavlink_msg_smart_battery_info_get_cells_in_series(msg); - smart_battery_info->discharge_maximum_current = mavlink_msg_smart_battery_info_get_discharge_maximum_current(msg); - smart_battery_info->discharge_maximum_burst_current = mavlink_msg_smart_battery_info_get_discharge_maximum_burst_current(msg); - mavlink_msg_smart_battery_info_get_manufacture_date(msg, smart_battery_info->manufacture_date); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_SMART_BATTERY_INFO_LEN? msg->len : MAVLINK_MSG_ID_SMART_BATTERY_INFO_LEN; - memset(smart_battery_info, 0, MAVLINK_MSG_ID_SMART_BATTERY_INFO_LEN); - memcpy(smart_battery_info, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_statustext.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_statustext.h deleted file mode 100644 index 78db7c60..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_statustext.h +++ /dev/null @@ -1,280 +0,0 @@ -#pragma once -// MESSAGE STATUSTEXT PACKING - -#define MAVLINK_MSG_ID_STATUSTEXT 253 - -MAVPACKED( -typedef struct __mavlink_statustext_t { - uint8_t severity; /*< Severity of status. Relies on the definitions within RFC-5424.*/ - char text[50]; /*< Status text message, without null termination character*/ - uint16_t id; /*< Unique (opaque) identifier for this statustext message. May be used to reassemble a logical long-statustext message from a sequence of chunks. A value of zero indicates this is the only chunk in the sequence and the message can be emitted immediately.*/ - uint8_t chunk_seq; /*< This chunk's sequence number; indexing is from zero. Any null character in the text field is taken to mean this was the last chunk.*/ -}) mavlink_statustext_t; - -#define MAVLINK_MSG_ID_STATUSTEXT_LEN 54 -#define MAVLINK_MSG_ID_STATUSTEXT_MIN_LEN 51 -#define MAVLINK_MSG_ID_253_LEN 54 -#define MAVLINK_MSG_ID_253_MIN_LEN 51 - -#define MAVLINK_MSG_ID_STATUSTEXT_CRC 83 -#define MAVLINK_MSG_ID_253_CRC 83 - -#define MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN 50 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_STATUSTEXT { \ - 253, \ - "STATUSTEXT", \ - 4, \ - { { "severity", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_statustext_t, severity) }, \ - { "text", NULL, MAVLINK_TYPE_CHAR, 50, 1, offsetof(mavlink_statustext_t, text) }, \ - { "id", NULL, MAVLINK_TYPE_UINT16_T, 0, 51, offsetof(mavlink_statustext_t, id) }, \ - { "chunk_seq", NULL, MAVLINK_TYPE_UINT8_T, 0, 53, offsetof(mavlink_statustext_t, chunk_seq) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_STATUSTEXT { \ - "STATUSTEXT", \ - 4, \ - { { "severity", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_statustext_t, severity) }, \ - { "text", NULL, MAVLINK_TYPE_CHAR, 50, 1, offsetof(mavlink_statustext_t, text) }, \ - { "id", NULL, MAVLINK_TYPE_UINT16_T, 0, 51, offsetof(mavlink_statustext_t, id) }, \ - { "chunk_seq", NULL, MAVLINK_TYPE_UINT8_T, 0, 53, offsetof(mavlink_statustext_t, chunk_seq) }, \ - } \ -} -#endif - -/** - * @brief Pack a statustext message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param severity Severity of status. Relies on the definitions within RFC-5424. - * @param text Status text message, without null termination character - * @param id Unique (opaque) identifier for this statustext message. May be used to reassemble a logical long-statustext message from a sequence of chunks. A value of zero indicates this is the only chunk in the sequence and the message can be emitted immediately. - * @param chunk_seq This chunk's sequence number; indexing is from zero. Any null character in the text field is taken to mean this was the last chunk. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_statustext_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t severity, const char *text, uint16_t id, uint8_t chunk_seq) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_STATUSTEXT_LEN]; - _mav_put_uint8_t(buf, 0, severity); - _mav_put_uint16_t(buf, 51, id); - _mav_put_uint8_t(buf, 53, chunk_seq); - _mav_put_char_array(buf, 1, text, 50); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_STATUSTEXT_LEN); -#else - mavlink_statustext_t packet; - packet.severity = severity; - packet.id = id; - packet.chunk_seq = chunk_seq; - mav_array_memcpy(packet.text, text, sizeof(char)*50); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_STATUSTEXT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_STATUSTEXT; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_STATUSTEXT_MIN_LEN, MAVLINK_MSG_ID_STATUSTEXT_LEN, MAVLINK_MSG_ID_STATUSTEXT_CRC); -} - -/** - * @brief Pack a statustext message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param severity Severity of status. Relies on the definitions within RFC-5424. - * @param text Status text message, without null termination character - * @param id Unique (opaque) identifier for this statustext message. May be used to reassemble a logical long-statustext message from a sequence of chunks. A value of zero indicates this is the only chunk in the sequence and the message can be emitted immediately. - * @param chunk_seq This chunk's sequence number; indexing is from zero. Any null character in the text field is taken to mean this was the last chunk. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_statustext_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t severity,const char *text,uint16_t id,uint8_t chunk_seq) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_STATUSTEXT_LEN]; - _mav_put_uint8_t(buf, 0, severity); - _mav_put_uint16_t(buf, 51, id); - _mav_put_uint8_t(buf, 53, chunk_seq); - _mav_put_char_array(buf, 1, text, 50); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_STATUSTEXT_LEN); -#else - mavlink_statustext_t packet; - packet.severity = severity; - packet.id = id; - packet.chunk_seq = chunk_seq; - mav_array_memcpy(packet.text, text, sizeof(char)*50); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_STATUSTEXT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_STATUSTEXT; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_STATUSTEXT_MIN_LEN, MAVLINK_MSG_ID_STATUSTEXT_LEN, MAVLINK_MSG_ID_STATUSTEXT_CRC); -} - -/** - * @brief Encode a statustext struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param statustext C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_statustext_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_statustext_t* statustext) -{ - return mavlink_msg_statustext_pack(system_id, component_id, msg, statustext->severity, statustext->text, statustext->id, statustext->chunk_seq); -} - -/** - * @brief Encode a statustext struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param statustext C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_statustext_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_statustext_t* statustext) -{ - return mavlink_msg_statustext_pack_chan(system_id, component_id, chan, msg, statustext->severity, statustext->text, statustext->id, statustext->chunk_seq); -} - -/** - * @brief Send a statustext message - * @param chan MAVLink channel to send the message - * - * @param severity Severity of status. Relies on the definitions within RFC-5424. - * @param text Status text message, without null termination character - * @param id Unique (opaque) identifier for this statustext message. May be used to reassemble a logical long-statustext message from a sequence of chunks. A value of zero indicates this is the only chunk in the sequence and the message can be emitted immediately. - * @param chunk_seq This chunk's sequence number; indexing is from zero. Any null character in the text field is taken to mean this was the last chunk. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_statustext_send(mavlink_channel_t chan, uint8_t severity, const char *text, uint16_t id, uint8_t chunk_seq) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_STATUSTEXT_LEN]; - _mav_put_uint8_t(buf, 0, severity); - _mav_put_uint16_t(buf, 51, id); - _mav_put_uint8_t(buf, 53, chunk_seq); - _mav_put_char_array(buf, 1, text, 50); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_STATUSTEXT, buf, MAVLINK_MSG_ID_STATUSTEXT_MIN_LEN, MAVLINK_MSG_ID_STATUSTEXT_LEN, MAVLINK_MSG_ID_STATUSTEXT_CRC); -#else - mavlink_statustext_t packet; - packet.severity = severity; - packet.id = id; - packet.chunk_seq = chunk_seq; - mav_array_memcpy(packet.text, text, sizeof(char)*50); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_STATUSTEXT, (const char *)&packet, MAVLINK_MSG_ID_STATUSTEXT_MIN_LEN, MAVLINK_MSG_ID_STATUSTEXT_LEN, MAVLINK_MSG_ID_STATUSTEXT_CRC); -#endif -} - -/** - * @brief Send a statustext message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_statustext_send_struct(mavlink_channel_t chan, const mavlink_statustext_t* statustext) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_statustext_send(chan, statustext->severity, statustext->text, statustext->id, statustext->chunk_seq); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_STATUSTEXT, (const char *)statustext, MAVLINK_MSG_ID_STATUSTEXT_MIN_LEN, MAVLINK_MSG_ID_STATUSTEXT_LEN, MAVLINK_MSG_ID_STATUSTEXT_CRC); -#endif -} - -#if MAVLINK_MSG_ID_STATUSTEXT_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_statustext_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t severity, const char *text, uint16_t id, uint8_t chunk_seq) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint8_t(buf, 0, severity); - _mav_put_uint16_t(buf, 51, id); - _mav_put_uint8_t(buf, 53, chunk_seq); - _mav_put_char_array(buf, 1, text, 50); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_STATUSTEXT, buf, MAVLINK_MSG_ID_STATUSTEXT_MIN_LEN, MAVLINK_MSG_ID_STATUSTEXT_LEN, MAVLINK_MSG_ID_STATUSTEXT_CRC); -#else - mavlink_statustext_t *packet = (mavlink_statustext_t *)msgbuf; - packet->severity = severity; - packet->id = id; - packet->chunk_seq = chunk_seq; - mav_array_memcpy(packet->text, text, sizeof(char)*50); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_STATUSTEXT, (const char *)packet, MAVLINK_MSG_ID_STATUSTEXT_MIN_LEN, MAVLINK_MSG_ID_STATUSTEXT_LEN, MAVLINK_MSG_ID_STATUSTEXT_CRC); -#endif -} -#endif - -#endif - -// MESSAGE STATUSTEXT UNPACKING - - -/** - * @brief Get field severity from statustext message - * - * @return Severity of status. Relies on the definitions within RFC-5424. - */ -static inline uint8_t mavlink_msg_statustext_get_severity(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 0); -} - -/** - * @brief Get field text from statustext message - * - * @return Status text message, without null termination character - */ -static inline uint16_t mavlink_msg_statustext_get_text(const mavlink_message_t* msg, char *text) -{ - return _MAV_RETURN_char_array(msg, text, 50, 1); -} - -/** - * @brief Get field id from statustext message - * - * @return Unique (opaque) identifier for this statustext message. May be used to reassemble a logical long-statustext message from a sequence of chunks. A value of zero indicates this is the only chunk in the sequence and the message can be emitted immediately. - */ -static inline uint16_t mavlink_msg_statustext_get_id(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 51); -} - -/** - * @brief Get field chunk_seq from statustext message - * - * @return This chunk's sequence number; indexing is from zero. Any null character in the text field is taken to mean this was the last chunk. - */ -static inline uint8_t mavlink_msg_statustext_get_chunk_seq(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 53); -} - -/** - * @brief Decode a statustext message into a struct - * - * @param msg The message to decode - * @param statustext C-struct to decode the message contents into - */ -static inline void mavlink_msg_statustext_decode(const mavlink_message_t* msg, mavlink_statustext_t* statustext) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - statustext->severity = mavlink_msg_statustext_get_severity(msg); - mavlink_msg_statustext_get_text(msg, statustext->text); - statustext->id = mavlink_msg_statustext_get_id(msg); - statustext->chunk_seq = mavlink_msg_statustext_get_chunk_seq(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_STATUSTEXT_LEN? msg->len : MAVLINK_MSG_ID_STATUSTEXT_LEN; - memset(statustext, 0, MAVLINK_MSG_ID_STATUSTEXT_LEN); - memcpy(statustext, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_storage_information.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_storage_information.h deleted file mode 100644 index 94317f41..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_storage_information.h +++ /dev/null @@ -1,495 +0,0 @@ -#pragma once -// MESSAGE STORAGE_INFORMATION PACKING - -#define MAVLINK_MSG_ID_STORAGE_INFORMATION 261 - - -typedef struct __mavlink_storage_information_t { - uint32_t time_boot_ms; /*< [ms] Timestamp (time since system boot).*/ - float total_capacity; /*< [MiB] Total capacity. If storage is not ready (STORAGE_STATUS_READY) value will be ignored.*/ - float used_capacity; /*< [MiB] Used capacity. If storage is not ready (STORAGE_STATUS_READY) value will be ignored.*/ - float available_capacity; /*< [MiB] Available storage capacity. If storage is not ready (STORAGE_STATUS_READY) value will be ignored.*/ - float read_speed; /*< [MiB/s] Read speed.*/ - float write_speed; /*< [MiB/s] Write speed.*/ - uint8_t storage_id; /*< Storage ID (1 for first, 2 for second, etc.)*/ - uint8_t storage_count; /*< Number of storage devices*/ - uint8_t status; /*< Status of storage*/ - uint8_t type; /*< Type of storage*/ - char name[32]; /*< Textual storage name to be used in UI (microSD 1, Internal Memory, etc.) This is a NULL terminated string. If it is exactly 32 characters long, add a terminating NULL. If this string is empty, the generic type is shown to the user.*/ - uint8_t storage_usage; /*< Flags indicating whether this instance is preferred storage for photos, videos, etc. - Note: Implementations should initially set the flags on the system-default storage id used for saving media (if possible/supported). - This setting can then be overridden using MAV_CMD_SET_STORAGE_USAGE. - If the media usage flags are not set, a GCS may assume storage ID 1 is the default storage for all media types.*/ -} mavlink_storage_information_t; - -#define MAVLINK_MSG_ID_STORAGE_INFORMATION_LEN 61 -#define MAVLINK_MSG_ID_STORAGE_INFORMATION_MIN_LEN 27 -#define MAVLINK_MSG_ID_261_LEN 61 -#define MAVLINK_MSG_ID_261_MIN_LEN 27 - -#define MAVLINK_MSG_ID_STORAGE_INFORMATION_CRC 179 -#define MAVLINK_MSG_ID_261_CRC 179 - -#define MAVLINK_MSG_STORAGE_INFORMATION_FIELD_NAME_LEN 32 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_STORAGE_INFORMATION { \ - 261, \ - "STORAGE_INFORMATION", \ - 12, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_storage_information_t, time_boot_ms) }, \ - { "storage_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_storage_information_t, storage_id) }, \ - { "storage_count", NULL, MAVLINK_TYPE_UINT8_T, 0, 25, offsetof(mavlink_storage_information_t, storage_count) }, \ - { "status", NULL, MAVLINK_TYPE_UINT8_T, 0, 26, offsetof(mavlink_storage_information_t, status) }, \ - { "total_capacity", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_storage_information_t, total_capacity) }, \ - { "used_capacity", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_storage_information_t, used_capacity) }, \ - { "available_capacity", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_storage_information_t, available_capacity) }, \ - { "read_speed", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_storage_information_t, read_speed) }, \ - { "write_speed", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_storage_information_t, write_speed) }, \ - { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 27, offsetof(mavlink_storage_information_t, type) }, \ - { "name", NULL, MAVLINK_TYPE_CHAR, 32, 28, offsetof(mavlink_storage_information_t, name) }, \ - { "storage_usage", NULL, MAVLINK_TYPE_UINT8_T, 0, 60, offsetof(mavlink_storage_information_t, storage_usage) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_STORAGE_INFORMATION { \ - "STORAGE_INFORMATION", \ - 12, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_storage_information_t, time_boot_ms) }, \ - { "storage_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_storage_information_t, storage_id) }, \ - { "storage_count", NULL, MAVLINK_TYPE_UINT8_T, 0, 25, offsetof(mavlink_storage_information_t, storage_count) }, \ - { "status", NULL, MAVLINK_TYPE_UINT8_T, 0, 26, offsetof(mavlink_storage_information_t, status) }, \ - { "total_capacity", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_storage_information_t, total_capacity) }, \ - { "used_capacity", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_storage_information_t, used_capacity) }, \ - { "available_capacity", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_storage_information_t, available_capacity) }, \ - { "read_speed", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_storage_information_t, read_speed) }, \ - { "write_speed", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_storage_information_t, write_speed) }, \ - { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 27, offsetof(mavlink_storage_information_t, type) }, \ - { "name", NULL, MAVLINK_TYPE_CHAR, 32, 28, offsetof(mavlink_storage_information_t, name) }, \ - { "storage_usage", NULL, MAVLINK_TYPE_UINT8_T, 0, 60, offsetof(mavlink_storage_information_t, storage_usage) }, \ - } \ -} -#endif - -/** - * @brief Pack a storage_information message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param time_boot_ms [ms] Timestamp (time since system boot). - * @param storage_id Storage ID (1 for first, 2 for second, etc.) - * @param storage_count Number of storage devices - * @param status Status of storage - * @param total_capacity [MiB] Total capacity. If storage is not ready (STORAGE_STATUS_READY) value will be ignored. - * @param used_capacity [MiB] Used capacity. If storage is not ready (STORAGE_STATUS_READY) value will be ignored. - * @param available_capacity [MiB] Available storage capacity. If storage is not ready (STORAGE_STATUS_READY) value will be ignored. - * @param read_speed [MiB/s] Read speed. - * @param write_speed [MiB/s] Write speed. - * @param type Type of storage - * @param name Textual storage name to be used in UI (microSD 1, Internal Memory, etc.) This is a NULL terminated string. If it is exactly 32 characters long, add a terminating NULL. If this string is empty, the generic type is shown to the user. - * @param storage_usage Flags indicating whether this instance is preferred storage for photos, videos, etc. - Note: Implementations should initially set the flags on the system-default storage id used for saving media (if possible/supported). - This setting can then be overridden using MAV_CMD_SET_STORAGE_USAGE. - If the media usage flags are not set, a GCS may assume storage ID 1 is the default storage for all media types. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_storage_information_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint32_t time_boot_ms, uint8_t storage_id, uint8_t storage_count, uint8_t status, float total_capacity, float used_capacity, float available_capacity, float read_speed, float write_speed, uint8_t type, const char *name, uint8_t storage_usage) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_STORAGE_INFORMATION_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, total_capacity); - _mav_put_float(buf, 8, used_capacity); - _mav_put_float(buf, 12, available_capacity); - _mav_put_float(buf, 16, read_speed); - _mav_put_float(buf, 20, write_speed); - _mav_put_uint8_t(buf, 24, storage_id); - _mav_put_uint8_t(buf, 25, storage_count); - _mav_put_uint8_t(buf, 26, status); - _mav_put_uint8_t(buf, 27, type); - _mav_put_uint8_t(buf, 60, storage_usage); - _mav_put_char_array(buf, 28, name, 32); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_STORAGE_INFORMATION_LEN); -#else - mavlink_storage_information_t packet; - packet.time_boot_ms = time_boot_ms; - packet.total_capacity = total_capacity; - packet.used_capacity = used_capacity; - packet.available_capacity = available_capacity; - packet.read_speed = read_speed; - packet.write_speed = write_speed; - packet.storage_id = storage_id; - packet.storage_count = storage_count; - packet.status = status; - packet.type = type; - packet.storage_usage = storage_usage; - mav_array_memcpy(packet.name, name, sizeof(char)*32); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_STORAGE_INFORMATION_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_STORAGE_INFORMATION; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_STORAGE_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_STORAGE_INFORMATION_LEN, MAVLINK_MSG_ID_STORAGE_INFORMATION_CRC); -} - -/** - * @brief Pack a storage_information message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_boot_ms [ms] Timestamp (time since system boot). - * @param storage_id Storage ID (1 for first, 2 for second, etc.) - * @param storage_count Number of storage devices - * @param status Status of storage - * @param total_capacity [MiB] Total capacity. If storage is not ready (STORAGE_STATUS_READY) value will be ignored. - * @param used_capacity [MiB] Used capacity. If storage is not ready (STORAGE_STATUS_READY) value will be ignored. - * @param available_capacity [MiB] Available storage capacity. If storage is not ready (STORAGE_STATUS_READY) value will be ignored. - * @param read_speed [MiB/s] Read speed. - * @param write_speed [MiB/s] Write speed. - * @param type Type of storage - * @param name Textual storage name to be used in UI (microSD 1, Internal Memory, etc.) This is a NULL terminated string. If it is exactly 32 characters long, add a terminating NULL. If this string is empty, the generic type is shown to the user. - * @param storage_usage Flags indicating whether this instance is preferred storage for photos, videos, etc. - Note: Implementations should initially set the flags on the system-default storage id used for saving media (if possible/supported). - This setting can then be overridden using MAV_CMD_SET_STORAGE_USAGE. - If the media usage flags are not set, a GCS may assume storage ID 1 is the default storage for all media types. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_storage_information_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint32_t time_boot_ms,uint8_t storage_id,uint8_t storage_count,uint8_t status,float total_capacity,float used_capacity,float available_capacity,float read_speed,float write_speed,uint8_t type,const char *name,uint8_t storage_usage) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_STORAGE_INFORMATION_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, total_capacity); - _mav_put_float(buf, 8, used_capacity); - _mav_put_float(buf, 12, available_capacity); - _mav_put_float(buf, 16, read_speed); - _mav_put_float(buf, 20, write_speed); - _mav_put_uint8_t(buf, 24, storage_id); - _mav_put_uint8_t(buf, 25, storage_count); - _mav_put_uint8_t(buf, 26, status); - _mav_put_uint8_t(buf, 27, type); - _mav_put_uint8_t(buf, 60, storage_usage); - _mav_put_char_array(buf, 28, name, 32); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_STORAGE_INFORMATION_LEN); -#else - mavlink_storage_information_t packet; - packet.time_boot_ms = time_boot_ms; - packet.total_capacity = total_capacity; - packet.used_capacity = used_capacity; - packet.available_capacity = available_capacity; - packet.read_speed = read_speed; - packet.write_speed = write_speed; - packet.storage_id = storage_id; - packet.storage_count = storage_count; - packet.status = status; - packet.type = type; - packet.storage_usage = storage_usage; - mav_array_memcpy(packet.name, name, sizeof(char)*32); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_STORAGE_INFORMATION_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_STORAGE_INFORMATION; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_STORAGE_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_STORAGE_INFORMATION_LEN, MAVLINK_MSG_ID_STORAGE_INFORMATION_CRC); -} - -/** - * @brief Encode a storage_information struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param storage_information C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_storage_information_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_storage_information_t* storage_information) -{ - return mavlink_msg_storage_information_pack(system_id, component_id, msg, storage_information->time_boot_ms, storage_information->storage_id, storage_information->storage_count, storage_information->status, storage_information->total_capacity, storage_information->used_capacity, storage_information->available_capacity, storage_information->read_speed, storage_information->write_speed, storage_information->type, storage_information->name, storage_information->storage_usage); -} - -/** - * @brief Encode a storage_information struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param storage_information C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_storage_information_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_storage_information_t* storage_information) -{ - return mavlink_msg_storage_information_pack_chan(system_id, component_id, chan, msg, storage_information->time_boot_ms, storage_information->storage_id, storage_information->storage_count, storage_information->status, storage_information->total_capacity, storage_information->used_capacity, storage_information->available_capacity, storage_information->read_speed, storage_information->write_speed, storage_information->type, storage_information->name, storage_information->storage_usage); -} - -/** - * @brief Send a storage_information message - * @param chan MAVLink channel to send the message - * - * @param time_boot_ms [ms] Timestamp (time since system boot). - * @param storage_id Storage ID (1 for first, 2 for second, etc.) - * @param storage_count Number of storage devices - * @param status Status of storage - * @param total_capacity [MiB] Total capacity. If storage is not ready (STORAGE_STATUS_READY) value will be ignored. - * @param used_capacity [MiB] Used capacity. If storage is not ready (STORAGE_STATUS_READY) value will be ignored. - * @param available_capacity [MiB] Available storage capacity. If storage is not ready (STORAGE_STATUS_READY) value will be ignored. - * @param read_speed [MiB/s] Read speed. - * @param write_speed [MiB/s] Write speed. - * @param type Type of storage - * @param name Textual storage name to be used in UI (microSD 1, Internal Memory, etc.) This is a NULL terminated string. If it is exactly 32 characters long, add a terminating NULL. If this string is empty, the generic type is shown to the user. - * @param storage_usage Flags indicating whether this instance is preferred storage for photos, videos, etc. - Note: Implementations should initially set the flags on the system-default storage id used for saving media (if possible/supported). - This setting can then be overridden using MAV_CMD_SET_STORAGE_USAGE. - If the media usage flags are not set, a GCS may assume storage ID 1 is the default storage for all media types. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_storage_information_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t storage_id, uint8_t storage_count, uint8_t status, float total_capacity, float used_capacity, float available_capacity, float read_speed, float write_speed, uint8_t type, const char *name, uint8_t storage_usage) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_STORAGE_INFORMATION_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, total_capacity); - _mav_put_float(buf, 8, used_capacity); - _mav_put_float(buf, 12, available_capacity); - _mav_put_float(buf, 16, read_speed); - _mav_put_float(buf, 20, write_speed); - _mav_put_uint8_t(buf, 24, storage_id); - _mav_put_uint8_t(buf, 25, storage_count); - _mav_put_uint8_t(buf, 26, status); - _mav_put_uint8_t(buf, 27, type); - _mav_put_uint8_t(buf, 60, storage_usage); - _mav_put_char_array(buf, 28, name, 32); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_STORAGE_INFORMATION, buf, MAVLINK_MSG_ID_STORAGE_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_STORAGE_INFORMATION_LEN, MAVLINK_MSG_ID_STORAGE_INFORMATION_CRC); -#else - mavlink_storage_information_t packet; - packet.time_boot_ms = time_boot_ms; - packet.total_capacity = total_capacity; - packet.used_capacity = used_capacity; - packet.available_capacity = available_capacity; - packet.read_speed = read_speed; - packet.write_speed = write_speed; - packet.storage_id = storage_id; - packet.storage_count = storage_count; - packet.status = status; - packet.type = type; - packet.storage_usage = storage_usage; - mav_array_memcpy(packet.name, name, sizeof(char)*32); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_STORAGE_INFORMATION, (const char *)&packet, MAVLINK_MSG_ID_STORAGE_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_STORAGE_INFORMATION_LEN, MAVLINK_MSG_ID_STORAGE_INFORMATION_CRC); -#endif -} - -/** - * @brief Send a storage_information message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_storage_information_send_struct(mavlink_channel_t chan, const mavlink_storage_information_t* storage_information) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_storage_information_send(chan, storage_information->time_boot_ms, storage_information->storage_id, storage_information->storage_count, storage_information->status, storage_information->total_capacity, storage_information->used_capacity, storage_information->available_capacity, storage_information->read_speed, storage_information->write_speed, storage_information->type, storage_information->name, storage_information->storage_usage); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_STORAGE_INFORMATION, (const char *)storage_information, MAVLINK_MSG_ID_STORAGE_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_STORAGE_INFORMATION_LEN, MAVLINK_MSG_ID_STORAGE_INFORMATION_CRC); -#endif -} - -#if MAVLINK_MSG_ID_STORAGE_INFORMATION_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_storage_information_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t storage_id, uint8_t storage_count, uint8_t status, float total_capacity, float used_capacity, float available_capacity, float read_speed, float write_speed, uint8_t type, const char *name, uint8_t storage_usage) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, total_capacity); - _mav_put_float(buf, 8, used_capacity); - _mav_put_float(buf, 12, available_capacity); - _mav_put_float(buf, 16, read_speed); - _mav_put_float(buf, 20, write_speed); - _mav_put_uint8_t(buf, 24, storage_id); - _mav_put_uint8_t(buf, 25, storage_count); - _mav_put_uint8_t(buf, 26, status); - _mav_put_uint8_t(buf, 27, type); - _mav_put_uint8_t(buf, 60, storage_usage); - _mav_put_char_array(buf, 28, name, 32); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_STORAGE_INFORMATION, buf, MAVLINK_MSG_ID_STORAGE_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_STORAGE_INFORMATION_LEN, MAVLINK_MSG_ID_STORAGE_INFORMATION_CRC); -#else - mavlink_storage_information_t *packet = (mavlink_storage_information_t *)msgbuf; - packet->time_boot_ms = time_boot_ms; - packet->total_capacity = total_capacity; - packet->used_capacity = used_capacity; - packet->available_capacity = available_capacity; - packet->read_speed = read_speed; - packet->write_speed = write_speed; - packet->storage_id = storage_id; - packet->storage_count = storage_count; - packet->status = status; - packet->type = type; - packet->storage_usage = storage_usage; - mav_array_memcpy(packet->name, name, sizeof(char)*32); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_STORAGE_INFORMATION, (const char *)packet, MAVLINK_MSG_ID_STORAGE_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_STORAGE_INFORMATION_LEN, MAVLINK_MSG_ID_STORAGE_INFORMATION_CRC); -#endif -} -#endif - -#endif - -// MESSAGE STORAGE_INFORMATION UNPACKING - - -/** - * @brief Get field time_boot_ms from storage_information message - * - * @return [ms] Timestamp (time since system boot). - */ -static inline uint32_t mavlink_msg_storage_information_get_time_boot_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field storage_id from storage_information message - * - * @return Storage ID (1 for first, 2 for second, etc.) - */ -static inline uint8_t mavlink_msg_storage_information_get_storage_id(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 24); -} - -/** - * @brief Get field storage_count from storage_information message - * - * @return Number of storage devices - */ -static inline uint8_t mavlink_msg_storage_information_get_storage_count(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 25); -} - -/** - * @brief Get field status from storage_information message - * - * @return Status of storage - */ -static inline uint8_t mavlink_msg_storage_information_get_status(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 26); -} - -/** - * @brief Get field total_capacity from storage_information message - * - * @return [MiB] Total capacity. If storage is not ready (STORAGE_STATUS_READY) value will be ignored. - */ -static inline float mavlink_msg_storage_information_get_total_capacity(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 4); -} - -/** - * @brief Get field used_capacity from storage_information message - * - * @return [MiB] Used capacity. If storage is not ready (STORAGE_STATUS_READY) value will be ignored. - */ -static inline float mavlink_msg_storage_information_get_used_capacity(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field available_capacity from storage_information message - * - * @return [MiB] Available storage capacity. If storage is not ready (STORAGE_STATUS_READY) value will be ignored. - */ -static inline float mavlink_msg_storage_information_get_available_capacity(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field read_speed from storage_information message - * - * @return [MiB/s] Read speed. - */ -static inline float mavlink_msg_storage_information_get_read_speed(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field write_speed from storage_information message - * - * @return [MiB/s] Write speed. - */ -static inline float mavlink_msg_storage_information_get_write_speed(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Get field type from storage_information message - * - * @return Type of storage - */ -static inline uint8_t mavlink_msg_storage_information_get_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 27); -} - -/** - * @brief Get field name from storage_information message - * - * @return Textual storage name to be used in UI (microSD 1, Internal Memory, etc.) This is a NULL terminated string. If it is exactly 32 characters long, add a terminating NULL. If this string is empty, the generic type is shown to the user. - */ -static inline uint16_t mavlink_msg_storage_information_get_name(const mavlink_message_t* msg, char *name) -{ - return _MAV_RETURN_char_array(msg, name, 32, 28); -} - -/** - * @brief Get field storage_usage from storage_information message - * - * @return Flags indicating whether this instance is preferred storage for photos, videos, etc. - Note: Implementations should initially set the flags on the system-default storage id used for saving media (if possible/supported). - This setting can then be overridden using MAV_CMD_SET_STORAGE_USAGE. - If the media usage flags are not set, a GCS may assume storage ID 1 is the default storage for all media types. - */ -static inline uint8_t mavlink_msg_storage_information_get_storage_usage(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 60); -} - -/** - * @brief Decode a storage_information message into a struct - * - * @param msg The message to decode - * @param storage_information C-struct to decode the message contents into - */ -static inline void mavlink_msg_storage_information_decode(const mavlink_message_t* msg, mavlink_storage_information_t* storage_information) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - storage_information->time_boot_ms = mavlink_msg_storage_information_get_time_boot_ms(msg); - storage_information->total_capacity = mavlink_msg_storage_information_get_total_capacity(msg); - storage_information->used_capacity = mavlink_msg_storage_information_get_used_capacity(msg); - storage_information->available_capacity = mavlink_msg_storage_information_get_available_capacity(msg); - storage_information->read_speed = mavlink_msg_storage_information_get_read_speed(msg); - storage_information->write_speed = mavlink_msg_storage_information_get_write_speed(msg); - storage_information->storage_id = mavlink_msg_storage_information_get_storage_id(msg); - storage_information->storage_count = mavlink_msg_storage_information_get_storage_count(msg); - storage_information->status = mavlink_msg_storage_information_get_status(msg); - storage_information->type = mavlink_msg_storage_information_get_type(msg); - mavlink_msg_storage_information_get_name(msg, storage_information->name); - storage_information->storage_usage = mavlink_msg_storage_information_get_storage_usage(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_STORAGE_INFORMATION_LEN? msg->len : MAVLINK_MSG_ID_STORAGE_INFORMATION_LEN; - memset(storage_information, 0, MAVLINK_MSG_ID_STORAGE_INFORMATION_LEN); - memcpy(storage_information, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_supported_tunes.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_supported_tunes.h deleted file mode 100644 index 65862c2e..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_supported_tunes.h +++ /dev/null @@ -1,263 +0,0 @@ -#pragma once -// MESSAGE SUPPORTED_TUNES PACKING - -#define MAVLINK_MSG_ID_SUPPORTED_TUNES 401 - - -typedef struct __mavlink_supported_tunes_t { - uint32_t format; /*< Bitfield of supported tune formats.*/ - uint8_t target_system; /*< System ID*/ - uint8_t target_component; /*< Component ID*/ -} mavlink_supported_tunes_t; - -#define MAVLINK_MSG_ID_SUPPORTED_TUNES_LEN 6 -#define MAVLINK_MSG_ID_SUPPORTED_TUNES_MIN_LEN 6 -#define MAVLINK_MSG_ID_401_LEN 6 -#define MAVLINK_MSG_ID_401_MIN_LEN 6 - -#define MAVLINK_MSG_ID_SUPPORTED_TUNES_CRC 183 -#define MAVLINK_MSG_ID_401_CRC 183 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_SUPPORTED_TUNES { \ - 401, \ - "SUPPORTED_TUNES", \ - 3, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_supported_tunes_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_supported_tunes_t, target_component) }, \ - { "format", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_supported_tunes_t, format) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_SUPPORTED_TUNES { \ - "SUPPORTED_TUNES", \ - 3, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_supported_tunes_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_supported_tunes_t, target_component) }, \ - { "format", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_supported_tunes_t, format) }, \ - } \ -} -#endif - -/** - * @brief Pack a supported_tunes message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID - * @param target_component Component ID - * @param format Bitfield of supported tune formats. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_supported_tunes_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component, uint32_t format) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SUPPORTED_TUNES_LEN]; - _mav_put_uint32_t(buf, 0, format); - _mav_put_uint8_t(buf, 4, target_system); - _mav_put_uint8_t(buf, 5, target_component); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SUPPORTED_TUNES_LEN); -#else - mavlink_supported_tunes_t packet; - packet.format = format; - packet.target_system = target_system; - packet.target_component = target_component; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SUPPORTED_TUNES_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SUPPORTED_TUNES; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SUPPORTED_TUNES_MIN_LEN, MAVLINK_MSG_ID_SUPPORTED_TUNES_LEN, MAVLINK_MSG_ID_SUPPORTED_TUNES_CRC); -} - -/** - * @brief Pack a supported_tunes message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @param format Bitfield of supported tune formats. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_supported_tunes_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component,uint32_t format) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SUPPORTED_TUNES_LEN]; - _mav_put_uint32_t(buf, 0, format); - _mav_put_uint8_t(buf, 4, target_system); - _mav_put_uint8_t(buf, 5, target_component); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SUPPORTED_TUNES_LEN); -#else - mavlink_supported_tunes_t packet; - packet.format = format; - packet.target_system = target_system; - packet.target_component = target_component; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SUPPORTED_TUNES_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SUPPORTED_TUNES; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SUPPORTED_TUNES_MIN_LEN, MAVLINK_MSG_ID_SUPPORTED_TUNES_LEN, MAVLINK_MSG_ID_SUPPORTED_TUNES_CRC); -} - -/** - * @brief Encode a supported_tunes struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param supported_tunes C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_supported_tunes_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_supported_tunes_t* supported_tunes) -{ - return mavlink_msg_supported_tunes_pack(system_id, component_id, msg, supported_tunes->target_system, supported_tunes->target_component, supported_tunes->format); -} - -/** - * @brief Encode a supported_tunes struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param supported_tunes C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_supported_tunes_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_supported_tunes_t* supported_tunes) -{ - return mavlink_msg_supported_tunes_pack_chan(system_id, component_id, chan, msg, supported_tunes->target_system, supported_tunes->target_component, supported_tunes->format); -} - -/** - * @brief Send a supported_tunes message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param target_component Component ID - * @param format Bitfield of supported tune formats. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_supported_tunes_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint32_t format) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SUPPORTED_TUNES_LEN]; - _mav_put_uint32_t(buf, 0, format); - _mav_put_uint8_t(buf, 4, target_system); - _mav_put_uint8_t(buf, 5, target_component); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SUPPORTED_TUNES, buf, MAVLINK_MSG_ID_SUPPORTED_TUNES_MIN_LEN, MAVLINK_MSG_ID_SUPPORTED_TUNES_LEN, MAVLINK_MSG_ID_SUPPORTED_TUNES_CRC); -#else - mavlink_supported_tunes_t packet; - packet.format = format; - packet.target_system = target_system; - packet.target_component = target_component; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SUPPORTED_TUNES, (const char *)&packet, MAVLINK_MSG_ID_SUPPORTED_TUNES_MIN_LEN, MAVLINK_MSG_ID_SUPPORTED_TUNES_LEN, MAVLINK_MSG_ID_SUPPORTED_TUNES_CRC); -#endif -} - -/** - * @brief Send a supported_tunes message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_supported_tunes_send_struct(mavlink_channel_t chan, const mavlink_supported_tunes_t* supported_tunes) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_supported_tunes_send(chan, supported_tunes->target_system, supported_tunes->target_component, supported_tunes->format); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SUPPORTED_TUNES, (const char *)supported_tunes, MAVLINK_MSG_ID_SUPPORTED_TUNES_MIN_LEN, MAVLINK_MSG_ID_SUPPORTED_TUNES_LEN, MAVLINK_MSG_ID_SUPPORTED_TUNES_CRC); -#endif -} - -#if MAVLINK_MSG_ID_SUPPORTED_TUNES_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_supported_tunes_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint32_t format) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, format); - _mav_put_uint8_t(buf, 4, target_system); - _mav_put_uint8_t(buf, 5, target_component); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SUPPORTED_TUNES, buf, MAVLINK_MSG_ID_SUPPORTED_TUNES_MIN_LEN, MAVLINK_MSG_ID_SUPPORTED_TUNES_LEN, MAVLINK_MSG_ID_SUPPORTED_TUNES_CRC); -#else - mavlink_supported_tunes_t *packet = (mavlink_supported_tunes_t *)msgbuf; - packet->format = format; - packet->target_system = target_system; - packet->target_component = target_component; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SUPPORTED_TUNES, (const char *)packet, MAVLINK_MSG_ID_SUPPORTED_TUNES_MIN_LEN, MAVLINK_MSG_ID_SUPPORTED_TUNES_LEN, MAVLINK_MSG_ID_SUPPORTED_TUNES_CRC); -#endif -} -#endif - -#endif - -// MESSAGE SUPPORTED_TUNES UNPACKING - - -/** - * @brief Get field target_system from supported_tunes message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_supported_tunes_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 4); -} - -/** - * @brief Get field target_component from supported_tunes message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_supported_tunes_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 5); -} - -/** - * @brief Get field format from supported_tunes message - * - * @return Bitfield of supported tune formats. - */ -static inline uint32_t mavlink_msg_supported_tunes_get_format(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Decode a supported_tunes message into a struct - * - * @param msg The message to decode - * @param supported_tunes C-struct to decode the message contents into - */ -static inline void mavlink_msg_supported_tunes_decode(const mavlink_message_t* msg, mavlink_supported_tunes_t* supported_tunes) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - supported_tunes->format = mavlink_msg_supported_tunes_get_format(msg); - supported_tunes->target_system = mavlink_msg_supported_tunes_get_target_system(msg); - supported_tunes->target_component = mavlink_msg_supported_tunes_get_target_component(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_SUPPORTED_TUNES_LEN? msg->len : MAVLINK_MSG_ID_SUPPORTED_TUNES_LEN; - memset(supported_tunes, 0, MAVLINK_MSG_ID_SUPPORTED_TUNES_LEN); - memcpy(supported_tunes, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_sys_status.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_sys_status.h deleted file mode 100644 index fb589236..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_sys_status.h +++ /dev/null @@ -1,588 +0,0 @@ -#pragma once -// MESSAGE SYS_STATUS PACKING - -#define MAVLINK_MSG_ID_SYS_STATUS 1 - -MAVPACKED( -typedef struct __mavlink_sys_status_t { - uint32_t onboard_control_sensors_present; /*< Bitmap showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present.*/ - uint32_t onboard_control_sensors_enabled; /*< Bitmap showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled.*/ - uint32_t onboard_control_sensors_health; /*< Bitmap showing which onboard controllers and sensors have an error (or are operational). Value of 0: error. Value of 1: healthy.*/ - uint16_t load; /*< [d%] Maximum usage in percent of the mainloop time. Values: [0-1000] - should always be below 1000*/ - uint16_t voltage_battery; /*< [mV] Battery voltage, UINT16_MAX: Voltage not sent by autopilot*/ - int16_t current_battery; /*< [cA] Battery current, -1: Current not sent by autopilot*/ - uint16_t drop_rate_comm; /*< [c%] Communication drop rate, (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV)*/ - uint16_t errors_comm; /*< Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV)*/ - uint16_t errors_count1; /*< Autopilot-specific errors*/ - uint16_t errors_count2; /*< Autopilot-specific errors*/ - uint16_t errors_count3; /*< Autopilot-specific errors*/ - uint16_t errors_count4; /*< Autopilot-specific errors*/ - int8_t battery_remaining; /*< [%] Battery energy remaining, -1: Battery remaining energy not sent by autopilot*/ - uint32_t onboard_control_sensors_present_extended; /*< Bitmap showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present.*/ - uint32_t onboard_control_sensors_enabled_extended; /*< Bitmap showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled.*/ - uint32_t onboard_control_sensors_health_extended; /*< Bitmap showing which onboard controllers and sensors have an error (or are operational). Value of 0: error. Value of 1: healthy.*/ -}) mavlink_sys_status_t; - -#define MAVLINK_MSG_ID_SYS_STATUS_LEN 43 -#define MAVLINK_MSG_ID_SYS_STATUS_MIN_LEN 31 -#define MAVLINK_MSG_ID_1_LEN 43 -#define MAVLINK_MSG_ID_1_MIN_LEN 31 - -#define MAVLINK_MSG_ID_SYS_STATUS_CRC 124 -#define MAVLINK_MSG_ID_1_CRC 124 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_SYS_STATUS { \ - 1, \ - "SYS_STATUS", \ - 16, \ - { { "onboard_control_sensors_present", "0x%04x", MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_sys_status_t, onboard_control_sensors_present) }, \ - { "onboard_control_sensors_enabled", "0x%04x", MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_sys_status_t, onboard_control_sensors_enabled) }, \ - { "onboard_control_sensors_health", "0x%04x", MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_sys_status_t, onboard_control_sensors_health) }, \ - { "load", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_sys_status_t, load) }, \ - { "voltage_battery", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_sys_status_t, voltage_battery) }, \ - { "current_battery", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_sys_status_t, current_battery) }, \ - { "battery_remaining", NULL, MAVLINK_TYPE_INT8_T, 0, 30, offsetof(mavlink_sys_status_t, battery_remaining) }, \ - { "drop_rate_comm", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_sys_status_t, drop_rate_comm) }, \ - { "errors_comm", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_sys_status_t, errors_comm) }, \ - { "errors_count1", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_sys_status_t, errors_count1) }, \ - { "errors_count2", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_sys_status_t, errors_count2) }, \ - { "errors_count3", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_sys_status_t, errors_count3) }, \ - { "errors_count4", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_sys_status_t, errors_count4) }, \ - { "onboard_control_sensors_present_extended", "0x%04x", MAVLINK_TYPE_UINT32_T, 0, 31, offsetof(mavlink_sys_status_t, onboard_control_sensors_present_extended) }, \ - { "onboard_control_sensors_enabled_extended", "0x%04x", MAVLINK_TYPE_UINT32_T, 0, 35, offsetof(mavlink_sys_status_t, onboard_control_sensors_enabled_extended) }, \ - { "onboard_control_sensors_health_extended", "0x%04x", MAVLINK_TYPE_UINT32_T, 0, 39, offsetof(mavlink_sys_status_t, onboard_control_sensors_health_extended) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_SYS_STATUS { \ - "SYS_STATUS", \ - 16, \ - { { "onboard_control_sensors_present", "0x%04x", MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_sys_status_t, onboard_control_sensors_present) }, \ - { "onboard_control_sensors_enabled", "0x%04x", MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_sys_status_t, onboard_control_sensors_enabled) }, \ - { "onboard_control_sensors_health", "0x%04x", MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_sys_status_t, onboard_control_sensors_health) }, \ - { "load", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_sys_status_t, load) }, \ - { "voltage_battery", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_sys_status_t, voltage_battery) }, \ - { "current_battery", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_sys_status_t, current_battery) }, \ - { "battery_remaining", NULL, MAVLINK_TYPE_INT8_T, 0, 30, offsetof(mavlink_sys_status_t, battery_remaining) }, \ - { "drop_rate_comm", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_sys_status_t, drop_rate_comm) }, \ - { "errors_comm", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_sys_status_t, errors_comm) }, \ - { "errors_count1", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_sys_status_t, errors_count1) }, \ - { "errors_count2", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_sys_status_t, errors_count2) }, \ - { "errors_count3", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_sys_status_t, errors_count3) }, \ - { "errors_count4", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_sys_status_t, errors_count4) }, \ - { "onboard_control_sensors_present_extended", "0x%04x", MAVLINK_TYPE_UINT32_T, 0, 31, offsetof(mavlink_sys_status_t, onboard_control_sensors_present_extended) }, \ - { "onboard_control_sensors_enabled_extended", "0x%04x", MAVLINK_TYPE_UINT32_T, 0, 35, offsetof(mavlink_sys_status_t, onboard_control_sensors_enabled_extended) }, \ - { "onboard_control_sensors_health_extended", "0x%04x", MAVLINK_TYPE_UINT32_T, 0, 39, offsetof(mavlink_sys_status_t, onboard_control_sensors_health_extended) }, \ - } \ -} -#endif - -/** - * @brief Pack a sys_status message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param onboard_control_sensors_present Bitmap showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present. - * @param onboard_control_sensors_enabled Bitmap showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled. - * @param onboard_control_sensors_health Bitmap showing which onboard controllers and sensors have an error (or are operational). Value of 0: error. Value of 1: healthy. - * @param load [d%] Maximum usage in percent of the mainloop time. Values: [0-1000] - should always be below 1000 - * @param voltage_battery [mV] Battery voltage, UINT16_MAX: Voltage not sent by autopilot - * @param current_battery [cA] Battery current, -1: Current not sent by autopilot - * @param battery_remaining [%] Battery energy remaining, -1: Battery remaining energy not sent by autopilot - * @param drop_rate_comm [c%] Communication drop rate, (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) - * @param errors_comm Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) - * @param errors_count1 Autopilot-specific errors - * @param errors_count2 Autopilot-specific errors - * @param errors_count3 Autopilot-specific errors - * @param errors_count4 Autopilot-specific errors - * @param onboard_control_sensors_present_extended Bitmap showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present. - * @param onboard_control_sensors_enabled_extended Bitmap showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled. - * @param onboard_control_sensors_health_extended Bitmap showing which onboard controllers and sensors have an error (or are operational). Value of 0: error. Value of 1: healthy. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_sys_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint32_t onboard_control_sensors_present, uint32_t onboard_control_sensors_enabled, uint32_t onboard_control_sensors_health, uint16_t load, uint16_t voltage_battery, int16_t current_battery, int8_t battery_remaining, uint16_t drop_rate_comm, uint16_t errors_comm, uint16_t errors_count1, uint16_t errors_count2, uint16_t errors_count3, uint16_t errors_count4, uint32_t onboard_control_sensors_present_extended, uint32_t onboard_control_sensors_enabled_extended, uint32_t onboard_control_sensors_health_extended) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SYS_STATUS_LEN]; - _mav_put_uint32_t(buf, 0, onboard_control_sensors_present); - _mav_put_uint32_t(buf, 4, onboard_control_sensors_enabled); - _mav_put_uint32_t(buf, 8, onboard_control_sensors_health); - _mav_put_uint16_t(buf, 12, load); - _mav_put_uint16_t(buf, 14, voltage_battery); - _mav_put_int16_t(buf, 16, current_battery); - _mav_put_uint16_t(buf, 18, drop_rate_comm); - _mav_put_uint16_t(buf, 20, errors_comm); - _mav_put_uint16_t(buf, 22, errors_count1); - _mav_put_uint16_t(buf, 24, errors_count2); - _mav_put_uint16_t(buf, 26, errors_count3); - _mav_put_uint16_t(buf, 28, errors_count4); - _mav_put_int8_t(buf, 30, battery_remaining); - _mav_put_uint32_t(buf, 31, onboard_control_sensors_present_extended); - _mav_put_uint32_t(buf, 35, onboard_control_sensors_enabled_extended); - _mav_put_uint32_t(buf, 39, onboard_control_sensors_health_extended); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SYS_STATUS_LEN); -#else - mavlink_sys_status_t packet; - packet.onboard_control_sensors_present = onboard_control_sensors_present; - packet.onboard_control_sensors_enabled = onboard_control_sensors_enabled; - packet.onboard_control_sensors_health = onboard_control_sensors_health; - packet.load = load; - packet.voltage_battery = voltage_battery; - packet.current_battery = current_battery; - packet.drop_rate_comm = drop_rate_comm; - packet.errors_comm = errors_comm; - packet.errors_count1 = errors_count1; - packet.errors_count2 = errors_count2; - packet.errors_count3 = errors_count3; - packet.errors_count4 = errors_count4; - packet.battery_remaining = battery_remaining; - packet.onboard_control_sensors_present_extended = onboard_control_sensors_present_extended; - packet.onboard_control_sensors_enabled_extended = onboard_control_sensors_enabled_extended; - packet.onboard_control_sensors_health_extended = onboard_control_sensors_health_extended; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SYS_STATUS_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SYS_STATUS; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SYS_STATUS_MIN_LEN, MAVLINK_MSG_ID_SYS_STATUS_LEN, MAVLINK_MSG_ID_SYS_STATUS_CRC); -} - -/** - * @brief Pack a sys_status message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param onboard_control_sensors_present Bitmap showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present. - * @param onboard_control_sensors_enabled Bitmap showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled. - * @param onboard_control_sensors_health Bitmap showing which onboard controllers and sensors have an error (or are operational). Value of 0: error. Value of 1: healthy. - * @param load [d%] Maximum usage in percent of the mainloop time. Values: [0-1000] - should always be below 1000 - * @param voltage_battery [mV] Battery voltage, UINT16_MAX: Voltage not sent by autopilot - * @param current_battery [cA] Battery current, -1: Current not sent by autopilot - * @param battery_remaining [%] Battery energy remaining, -1: Battery remaining energy not sent by autopilot - * @param drop_rate_comm [c%] Communication drop rate, (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) - * @param errors_comm Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) - * @param errors_count1 Autopilot-specific errors - * @param errors_count2 Autopilot-specific errors - * @param errors_count3 Autopilot-specific errors - * @param errors_count4 Autopilot-specific errors - * @param onboard_control_sensors_present_extended Bitmap showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present. - * @param onboard_control_sensors_enabled_extended Bitmap showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled. - * @param onboard_control_sensors_health_extended Bitmap showing which onboard controllers and sensors have an error (or are operational). Value of 0: error. Value of 1: healthy. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_sys_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint32_t onboard_control_sensors_present,uint32_t onboard_control_sensors_enabled,uint32_t onboard_control_sensors_health,uint16_t load,uint16_t voltage_battery,int16_t current_battery,int8_t battery_remaining,uint16_t drop_rate_comm,uint16_t errors_comm,uint16_t errors_count1,uint16_t errors_count2,uint16_t errors_count3,uint16_t errors_count4,uint32_t onboard_control_sensors_present_extended,uint32_t onboard_control_sensors_enabled_extended,uint32_t onboard_control_sensors_health_extended) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SYS_STATUS_LEN]; - _mav_put_uint32_t(buf, 0, onboard_control_sensors_present); - _mav_put_uint32_t(buf, 4, onboard_control_sensors_enabled); - _mav_put_uint32_t(buf, 8, onboard_control_sensors_health); - _mav_put_uint16_t(buf, 12, load); - _mav_put_uint16_t(buf, 14, voltage_battery); - _mav_put_int16_t(buf, 16, current_battery); - _mav_put_uint16_t(buf, 18, drop_rate_comm); - _mav_put_uint16_t(buf, 20, errors_comm); - _mav_put_uint16_t(buf, 22, errors_count1); - _mav_put_uint16_t(buf, 24, errors_count2); - _mav_put_uint16_t(buf, 26, errors_count3); - _mav_put_uint16_t(buf, 28, errors_count4); - _mav_put_int8_t(buf, 30, battery_remaining); - _mav_put_uint32_t(buf, 31, onboard_control_sensors_present_extended); - _mav_put_uint32_t(buf, 35, onboard_control_sensors_enabled_extended); - _mav_put_uint32_t(buf, 39, onboard_control_sensors_health_extended); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SYS_STATUS_LEN); -#else - mavlink_sys_status_t packet; - packet.onboard_control_sensors_present = onboard_control_sensors_present; - packet.onboard_control_sensors_enabled = onboard_control_sensors_enabled; - packet.onboard_control_sensors_health = onboard_control_sensors_health; - packet.load = load; - packet.voltage_battery = voltage_battery; - packet.current_battery = current_battery; - packet.drop_rate_comm = drop_rate_comm; - packet.errors_comm = errors_comm; - packet.errors_count1 = errors_count1; - packet.errors_count2 = errors_count2; - packet.errors_count3 = errors_count3; - packet.errors_count4 = errors_count4; - packet.battery_remaining = battery_remaining; - packet.onboard_control_sensors_present_extended = onboard_control_sensors_present_extended; - packet.onboard_control_sensors_enabled_extended = onboard_control_sensors_enabled_extended; - packet.onboard_control_sensors_health_extended = onboard_control_sensors_health_extended; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SYS_STATUS_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SYS_STATUS; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SYS_STATUS_MIN_LEN, MAVLINK_MSG_ID_SYS_STATUS_LEN, MAVLINK_MSG_ID_SYS_STATUS_CRC); -} - -/** - * @brief Encode a sys_status struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param sys_status C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_sys_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_sys_status_t* sys_status) -{ - return mavlink_msg_sys_status_pack(system_id, component_id, msg, sys_status->onboard_control_sensors_present, sys_status->onboard_control_sensors_enabled, sys_status->onboard_control_sensors_health, sys_status->load, sys_status->voltage_battery, sys_status->current_battery, sys_status->battery_remaining, sys_status->drop_rate_comm, sys_status->errors_comm, sys_status->errors_count1, sys_status->errors_count2, sys_status->errors_count3, sys_status->errors_count4, sys_status->onboard_control_sensors_present_extended, sys_status->onboard_control_sensors_enabled_extended, sys_status->onboard_control_sensors_health_extended); -} - -/** - * @brief Encode a sys_status struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param sys_status C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_sys_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_sys_status_t* sys_status) -{ - return mavlink_msg_sys_status_pack_chan(system_id, component_id, chan, msg, sys_status->onboard_control_sensors_present, sys_status->onboard_control_sensors_enabled, sys_status->onboard_control_sensors_health, sys_status->load, sys_status->voltage_battery, sys_status->current_battery, sys_status->battery_remaining, sys_status->drop_rate_comm, sys_status->errors_comm, sys_status->errors_count1, sys_status->errors_count2, sys_status->errors_count3, sys_status->errors_count4, sys_status->onboard_control_sensors_present_extended, sys_status->onboard_control_sensors_enabled_extended, sys_status->onboard_control_sensors_health_extended); -} - -/** - * @brief Send a sys_status message - * @param chan MAVLink channel to send the message - * - * @param onboard_control_sensors_present Bitmap showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present. - * @param onboard_control_sensors_enabled Bitmap showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled. - * @param onboard_control_sensors_health Bitmap showing which onboard controllers and sensors have an error (or are operational). Value of 0: error. Value of 1: healthy. - * @param load [d%] Maximum usage in percent of the mainloop time. Values: [0-1000] - should always be below 1000 - * @param voltage_battery [mV] Battery voltage, UINT16_MAX: Voltage not sent by autopilot - * @param current_battery [cA] Battery current, -1: Current not sent by autopilot - * @param battery_remaining [%] Battery energy remaining, -1: Battery remaining energy not sent by autopilot - * @param drop_rate_comm [c%] Communication drop rate, (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) - * @param errors_comm Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) - * @param errors_count1 Autopilot-specific errors - * @param errors_count2 Autopilot-specific errors - * @param errors_count3 Autopilot-specific errors - * @param errors_count4 Autopilot-specific errors - * @param onboard_control_sensors_present_extended Bitmap showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present. - * @param onboard_control_sensors_enabled_extended Bitmap showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled. - * @param onboard_control_sensors_health_extended Bitmap showing which onboard controllers and sensors have an error (or are operational). Value of 0: error. Value of 1: healthy. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_sys_status_send(mavlink_channel_t chan, uint32_t onboard_control_sensors_present, uint32_t onboard_control_sensors_enabled, uint32_t onboard_control_sensors_health, uint16_t load, uint16_t voltage_battery, int16_t current_battery, int8_t battery_remaining, uint16_t drop_rate_comm, uint16_t errors_comm, uint16_t errors_count1, uint16_t errors_count2, uint16_t errors_count3, uint16_t errors_count4, uint32_t onboard_control_sensors_present_extended, uint32_t onboard_control_sensors_enabled_extended, uint32_t onboard_control_sensors_health_extended) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SYS_STATUS_LEN]; - _mav_put_uint32_t(buf, 0, onboard_control_sensors_present); - _mav_put_uint32_t(buf, 4, onboard_control_sensors_enabled); - _mav_put_uint32_t(buf, 8, onboard_control_sensors_health); - _mav_put_uint16_t(buf, 12, load); - _mav_put_uint16_t(buf, 14, voltage_battery); - _mav_put_int16_t(buf, 16, current_battery); - _mav_put_uint16_t(buf, 18, drop_rate_comm); - _mav_put_uint16_t(buf, 20, errors_comm); - _mav_put_uint16_t(buf, 22, errors_count1); - _mav_put_uint16_t(buf, 24, errors_count2); - _mav_put_uint16_t(buf, 26, errors_count3); - _mav_put_uint16_t(buf, 28, errors_count4); - _mav_put_int8_t(buf, 30, battery_remaining); - _mav_put_uint32_t(buf, 31, onboard_control_sensors_present_extended); - _mav_put_uint32_t(buf, 35, onboard_control_sensors_enabled_extended); - _mav_put_uint32_t(buf, 39, onboard_control_sensors_health_extended); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYS_STATUS, buf, MAVLINK_MSG_ID_SYS_STATUS_MIN_LEN, MAVLINK_MSG_ID_SYS_STATUS_LEN, MAVLINK_MSG_ID_SYS_STATUS_CRC); -#else - mavlink_sys_status_t packet; - packet.onboard_control_sensors_present = onboard_control_sensors_present; - packet.onboard_control_sensors_enabled = onboard_control_sensors_enabled; - packet.onboard_control_sensors_health = onboard_control_sensors_health; - packet.load = load; - packet.voltage_battery = voltage_battery; - packet.current_battery = current_battery; - packet.drop_rate_comm = drop_rate_comm; - packet.errors_comm = errors_comm; - packet.errors_count1 = errors_count1; - packet.errors_count2 = errors_count2; - packet.errors_count3 = errors_count3; - packet.errors_count4 = errors_count4; - packet.battery_remaining = battery_remaining; - packet.onboard_control_sensors_present_extended = onboard_control_sensors_present_extended; - packet.onboard_control_sensors_enabled_extended = onboard_control_sensors_enabled_extended; - packet.onboard_control_sensors_health_extended = onboard_control_sensors_health_extended; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYS_STATUS, (const char *)&packet, MAVLINK_MSG_ID_SYS_STATUS_MIN_LEN, MAVLINK_MSG_ID_SYS_STATUS_LEN, MAVLINK_MSG_ID_SYS_STATUS_CRC); -#endif -} - -/** - * @brief Send a sys_status message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_sys_status_send_struct(mavlink_channel_t chan, const mavlink_sys_status_t* sys_status) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_sys_status_send(chan, sys_status->onboard_control_sensors_present, sys_status->onboard_control_sensors_enabled, sys_status->onboard_control_sensors_health, sys_status->load, sys_status->voltage_battery, sys_status->current_battery, sys_status->battery_remaining, sys_status->drop_rate_comm, sys_status->errors_comm, sys_status->errors_count1, sys_status->errors_count2, sys_status->errors_count3, sys_status->errors_count4, sys_status->onboard_control_sensors_present_extended, sys_status->onboard_control_sensors_enabled_extended, sys_status->onboard_control_sensors_health_extended); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYS_STATUS, (const char *)sys_status, MAVLINK_MSG_ID_SYS_STATUS_MIN_LEN, MAVLINK_MSG_ID_SYS_STATUS_LEN, MAVLINK_MSG_ID_SYS_STATUS_CRC); -#endif -} - -#if MAVLINK_MSG_ID_SYS_STATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_sys_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t onboard_control_sensors_present, uint32_t onboard_control_sensors_enabled, uint32_t onboard_control_sensors_health, uint16_t load, uint16_t voltage_battery, int16_t current_battery, int8_t battery_remaining, uint16_t drop_rate_comm, uint16_t errors_comm, uint16_t errors_count1, uint16_t errors_count2, uint16_t errors_count3, uint16_t errors_count4, uint32_t onboard_control_sensors_present_extended, uint32_t onboard_control_sensors_enabled_extended, uint32_t onboard_control_sensors_health_extended) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, onboard_control_sensors_present); - _mav_put_uint32_t(buf, 4, onboard_control_sensors_enabled); - _mav_put_uint32_t(buf, 8, onboard_control_sensors_health); - _mav_put_uint16_t(buf, 12, load); - _mav_put_uint16_t(buf, 14, voltage_battery); - _mav_put_int16_t(buf, 16, current_battery); - _mav_put_uint16_t(buf, 18, drop_rate_comm); - _mav_put_uint16_t(buf, 20, errors_comm); - _mav_put_uint16_t(buf, 22, errors_count1); - _mav_put_uint16_t(buf, 24, errors_count2); - _mav_put_uint16_t(buf, 26, errors_count3); - _mav_put_uint16_t(buf, 28, errors_count4); - _mav_put_int8_t(buf, 30, battery_remaining); - _mav_put_uint32_t(buf, 31, onboard_control_sensors_present_extended); - _mav_put_uint32_t(buf, 35, onboard_control_sensors_enabled_extended); - _mav_put_uint32_t(buf, 39, onboard_control_sensors_health_extended); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYS_STATUS, buf, MAVLINK_MSG_ID_SYS_STATUS_MIN_LEN, MAVLINK_MSG_ID_SYS_STATUS_LEN, MAVLINK_MSG_ID_SYS_STATUS_CRC); -#else - mavlink_sys_status_t *packet = (mavlink_sys_status_t *)msgbuf; - packet->onboard_control_sensors_present = onboard_control_sensors_present; - packet->onboard_control_sensors_enabled = onboard_control_sensors_enabled; - packet->onboard_control_sensors_health = onboard_control_sensors_health; - packet->load = load; - packet->voltage_battery = voltage_battery; - packet->current_battery = current_battery; - packet->drop_rate_comm = drop_rate_comm; - packet->errors_comm = errors_comm; - packet->errors_count1 = errors_count1; - packet->errors_count2 = errors_count2; - packet->errors_count3 = errors_count3; - packet->errors_count4 = errors_count4; - packet->battery_remaining = battery_remaining; - packet->onboard_control_sensors_present_extended = onboard_control_sensors_present_extended; - packet->onboard_control_sensors_enabled_extended = onboard_control_sensors_enabled_extended; - packet->onboard_control_sensors_health_extended = onboard_control_sensors_health_extended; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYS_STATUS, (const char *)packet, MAVLINK_MSG_ID_SYS_STATUS_MIN_LEN, MAVLINK_MSG_ID_SYS_STATUS_LEN, MAVLINK_MSG_ID_SYS_STATUS_CRC); -#endif -} -#endif - -#endif - -// MESSAGE SYS_STATUS UNPACKING - - -/** - * @brief Get field onboard_control_sensors_present from sys_status message - * - * @return Bitmap showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present. - */ -static inline uint32_t mavlink_msg_sys_status_get_onboard_control_sensors_present(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field onboard_control_sensors_enabled from sys_status message - * - * @return Bitmap showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled. - */ -static inline uint32_t mavlink_msg_sys_status_get_onboard_control_sensors_enabled(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 4); -} - -/** - * @brief Get field onboard_control_sensors_health from sys_status message - * - * @return Bitmap showing which onboard controllers and sensors have an error (or are operational). Value of 0: error. Value of 1: healthy. - */ -static inline uint32_t mavlink_msg_sys_status_get_onboard_control_sensors_health(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 8); -} - -/** - * @brief Get field load from sys_status message - * - * @return [d%] Maximum usage in percent of the mainloop time. Values: [0-1000] - should always be below 1000 - */ -static inline uint16_t mavlink_msg_sys_status_get_load(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 12); -} - -/** - * @brief Get field voltage_battery from sys_status message - * - * @return [mV] Battery voltage, UINT16_MAX: Voltage not sent by autopilot - */ -static inline uint16_t mavlink_msg_sys_status_get_voltage_battery(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 14); -} - -/** - * @brief Get field current_battery from sys_status message - * - * @return [cA] Battery current, -1: Current not sent by autopilot - */ -static inline int16_t mavlink_msg_sys_status_get_current_battery(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 16); -} - -/** - * @brief Get field battery_remaining from sys_status message - * - * @return [%] Battery energy remaining, -1: Battery remaining energy not sent by autopilot - */ -static inline int8_t mavlink_msg_sys_status_get_battery_remaining(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int8_t(msg, 30); -} - -/** - * @brief Get field drop_rate_comm from sys_status message - * - * @return [c%] Communication drop rate, (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) - */ -static inline uint16_t mavlink_msg_sys_status_get_drop_rate_comm(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 18); -} - -/** - * @brief Get field errors_comm from sys_status message - * - * @return Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) - */ -static inline uint16_t mavlink_msg_sys_status_get_errors_comm(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 20); -} - -/** - * @brief Get field errors_count1 from sys_status message - * - * @return Autopilot-specific errors - */ -static inline uint16_t mavlink_msg_sys_status_get_errors_count1(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 22); -} - -/** - * @brief Get field errors_count2 from sys_status message - * - * @return Autopilot-specific errors - */ -static inline uint16_t mavlink_msg_sys_status_get_errors_count2(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 24); -} - -/** - * @brief Get field errors_count3 from sys_status message - * - * @return Autopilot-specific errors - */ -static inline uint16_t mavlink_msg_sys_status_get_errors_count3(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 26); -} - -/** - * @brief Get field errors_count4 from sys_status message - * - * @return Autopilot-specific errors - */ -static inline uint16_t mavlink_msg_sys_status_get_errors_count4(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 28); -} - -/** - * @brief Get field onboard_control_sensors_present_extended from sys_status message - * - * @return Bitmap showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present. - */ -static inline uint32_t mavlink_msg_sys_status_get_onboard_control_sensors_present_extended(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 31); -} - -/** - * @brief Get field onboard_control_sensors_enabled_extended from sys_status message - * - * @return Bitmap showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled. - */ -static inline uint32_t mavlink_msg_sys_status_get_onboard_control_sensors_enabled_extended(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 35); -} - -/** - * @brief Get field onboard_control_sensors_health_extended from sys_status message - * - * @return Bitmap showing which onboard controllers and sensors have an error (or are operational). Value of 0: error. Value of 1: healthy. - */ -static inline uint32_t mavlink_msg_sys_status_get_onboard_control_sensors_health_extended(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 39); -} - -/** - * @brief Decode a sys_status message into a struct - * - * @param msg The message to decode - * @param sys_status C-struct to decode the message contents into - */ -static inline void mavlink_msg_sys_status_decode(const mavlink_message_t* msg, mavlink_sys_status_t* sys_status) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - sys_status->onboard_control_sensors_present = mavlink_msg_sys_status_get_onboard_control_sensors_present(msg); - sys_status->onboard_control_sensors_enabled = mavlink_msg_sys_status_get_onboard_control_sensors_enabled(msg); - sys_status->onboard_control_sensors_health = mavlink_msg_sys_status_get_onboard_control_sensors_health(msg); - sys_status->load = mavlink_msg_sys_status_get_load(msg); - sys_status->voltage_battery = mavlink_msg_sys_status_get_voltage_battery(msg); - sys_status->current_battery = mavlink_msg_sys_status_get_current_battery(msg); - sys_status->drop_rate_comm = mavlink_msg_sys_status_get_drop_rate_comm(msg); - sys_status->errors_comm = mavlink_msg_sys_status_get_errors_comm(msg); - sys_status->errors_count1 = mavlink_msg_sys_status_get_errors_count1(msg); - sys_status->errors_count2 = mavlink_msg_sys_status_get_errors_count2(msg); - sys_status->errors_count3 = mavlink_msg_sys_status_get_errors_count3(msg); - sys_status->errors_count4 = mavlink_msg_sys_status_get_errors_count4(msg); - sys_status->battery_remaining = mavlink_msg_sys_status_get_battery_remaining(msg); - sys_status->onboard_control_sensors_present_extended = mavlink_msg_sys_status_get_onboard_control_sensors_present_extended(msg); - sys_status->onboard_control_sensors_enabled_extended = mavlink_msg_sys_status_get_onboard_control_sensors_enabled_extended(msg); - sys_status->onboard_control_sensors_health_extended = mavlink_msg_sys_status_get_onboard_control_sensors_health_extended(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_SYS_STATUS_LEN? msg->len : MAVLINK_MSG_ID_SYS_STATUS_LEN; - memset(sys_status, 0, MAVLINK_MSG_ID_SYS_STATUS_LEN); - memcpy(sys_status, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_system_time.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_system_time.h deleted file mode 100644 index 0b043636..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_system_time.h +++ /dev/null @@ -1,238 +0,0 @@ -#pragma once -// MESSAGE SYSTEM_TIME PACKING - -#define MAVLINK_MSG_ID_SYSTEM_TIME 2 - - -typedef struct __mavlink_system_time_t { - uint64_t time_unix_usec; /*< [us] Timestamp (UNIX epoch time).*/ - uint32_t time_boot_ms; /*< [ms] Timestamp (time since system boot).*/ -} mavlink_system_time_t; - -#define MAVLINK_MSG_ID_SYSTEM_TIME_LEN 12 -#define MAVLINK_MSG_ID_SYSTEM_TIME_MIN_LEN 12 -#define MAVLINK_MSG_ID_2_LEN 12 -#define MAVLINK_MSG_ID_2_MIN_LEN 12 - -#define MAVLINK_MSG_ID_SYSTEM_TIME_CRC 137 -#define MAVLINK_MSG_ID_2_CRC 137 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_SYSTEM_TIME { \ - 2, \ - "SYSTEM_TIME", \ - 2, \ - { { "time_unix_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_system_time_t, time_unix_usec) }, \ - { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_system_time_t, time_boot_ms) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_SYSTEM_TIME { \ - "SYSTEM_TIME", \ - 2, \ - { { "time_unix_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_system_time_t, time_unix_usec) }, \ - { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_system_time_t, time_boot_ms) }, \ - } \ -} -#endif - -/** - * @brief Pack a system_time message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param time_unix_usec [us] Timestamp (UNIX epoch time). - * @param time_boot_ms [ms] Timestamp (time since system boot). - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_system_time_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint64_t time_unix_usec, uint32_t time_boot_ms) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SYSTEM_TIME_LEN]; - _mav_put_uint64_t(buf, 0, time_unix_usec); - _mav_put_uint32_t(buf, 8, time_boot_ms); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SYSTEM_TIME_LEN); -#else - mavlink_system_time_t packet; - packet.time_unix_usec = time_unix_usec; - packet.time_boot_ms = time_boot_ms; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SYSTEM_TIME_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SYSTEM_TIME; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SYSTEM_TIME_MIN_LEN, MAVLINK_MSG_ID_SYSTEM_TIME_LEN, MAVLINK_MSG_ID_SYSTEM_TIME_CRC); -} - -/** - * @brief Pack a system_time message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_unix_usec [us] Timestamp (UNIX epoch time). - * @param time_boot_ms [ms] Timestamp (time since system boot). - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_system_time_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint64_t time_unix_usec,uint32_t time_boot_ms) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SYSTEM_TIME_LEN]; - _mav_put_uint64_t(buf, 0, time_unix_usec); - _mav_put_uint32_t(buf, 8, time_boot_ms); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SYSTEM_TIME_LEN); -#else - mavlink_system_time_t packet; - packet.time_unix_usec = time_unix_usec; - packet.time_boot_ms = time_boot_ms; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SYSTEM_TIME_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SYSTEM_TIME; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SYSTEM_TIME_MIN_LEN, MAVLINK_MSG_ID_SYSTEM_TIME_LEN, MAVLINK_MSG_ID_SYSTEM_TIME_CRC); -} - -/** - * @brief Encode a system_time struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param system_time C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_system_time_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_system_time_t* system_time) -{ - return mavlink_msg_system_time_pack(system_id, component_id, msg, system_time->time_unix_usec, system_time->time_boot_ms); -} - -/** - * @brief Encode a system_time struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param system_time C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_system_time_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_system_time_t* system_time) -{ - return mavlink_msg_system_time_pack_chan(system_id, component_id, chan, msg, system_time->time_unix_usec, system_time->time_boot_ms); -} - -/** - * @brief Send a system_time message - * @param chan MAVLink channel to send the message - * - * @param time_unix_usec [us] Timestamp (UNIX epoch time). - * @param time_boot_ms [ms] Timestamp (time since system boot). - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_system_time_send(mavlink_channel_t chan, uint64_t time_unix_usec, uint32_t time_boot_ms) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SYSTEM_TIME_LEN]; - _mav_put_uint64_t(buf, 0, time_unix_usec); - _mav_put_uint32_t(buf, 8, time_boot_ms); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYSTEM_TIME, buf, MAVLINK_MSG_ID_SYSTEM_TIME_MIN_LEN, MAVLINK_MSG_ID_SYSTEM_TIME_LEN, MAVLINK_MSG_ID_SYSTEM_TIME_CRC); -#else - mavlink_system_time_t packet; - packet.time_unix_usec = time_unix_usec; - packet.time_boot_ms = time_boot_ms; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYSTEM_TIME, (const char *)&packet, MAVLINK_MSG_ID_SYSTEM_TIME_MIN_LEN, MAVLINK_MSG_ID_SYSTEM_TIME_LEN, MAVLINK_MSG_ID_SYSTEM_TIME_CRC); -#endif -} - -/** - * @brief Send a system_time message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_system_time_send_struct(mavlink_channel_t chan, const mavlink_system_time_t* system_time) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_system_time_send(chan, system_time->time_unix_usec, system_time->time_boot_ms); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYSTEM_TIME, (const char *)system_time, MAVLINK_MSG_ID_SYSTEM_TIME_MIN_LEN, MAVLINK_MSG_ID_SYSTEM_TIME_LEN, MAVLINK_MSG_ID_SYSTEM_TIME_CRC); -#endif -} - -#if MAVLINK_MSG_ID_SYSTEM_TIME_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_system_time_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_unix_usec, uint32_t time_boot_ms) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, time_unix_usec); - _mav_put_uint32_t(buf, 8, time_boot_ms); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYSTEM_TIME, buf, MAVLINK_MSG_ID_SYSTEM_TIME_MIN_LEN, MAVLINK_MSG_ID_SYSTEM_TIME_LEN, MAVLINK_MSG_ID_SYSTEM_TIME_CRC); -#else - mavlink_system_time_t *packet = (mavlink_system_time_t *)msgbuf; - packet->time_unix_usec = time_unix_usec; - packet->time_boot_ms = time_boot_ms; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYSTEM_TIME, (const char *)packet, MAVLINK_MSG_ID_SYSTEM_TIME_MIN_LEN, MAVLINK_MSG_ID_SYSTEM_TIME_LEN, MAVLINK_MSG_ID_SYSTEM_TIME_CRC); -#endif -} -#endif - -#endif - -// MESSAGE SYSTEM_TIME UNPACKING - - -/** - * @brief Get field time_unix_usec from system_time message - * - * @return [us] Timestamp (UNIX epoch time). - */ -static inline uint64_t mavlink_msg_system_time_get_time_unix_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field time_boot_ms from system_time message - * - * @return [ms] Timestamp (time since system boot). - */ -static inline uint32_t mavlink_msg_system_time_get_time_boot_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 8); -} - -/** - * @brief Decode a system_time message into a struct - * - * @param msg The message to decode - * @param system_time C-struct to decode the message contents into - */ -static inline void mavlink_msg_system_time_decode(const mavlink_message_t* msg, mavlink_system_time_t* system_time) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - system_time->time_unix_usec = mavlink_msg_system_time_get_time_unix_usec(msg); - system_time->time_boot_ms = mavlink_msg_system_time_get_time_boot_ms(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_SYSTEM_TIME_LEN? msg->len : MAVLINK_MSG_ID_SYSTEM_TIME_LEN; - memset(system_time, 0, MAVLINK_MSG_ID_SYSTEM_TIME_LEN); - memcpy(system_time, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_terrain_check.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_terrain_check.h deleted file mode 100644 index eaadfa15..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_terrain_check.h +++ /dev/null @@ -1,238 +0,0 @@ -#pragma once -// MESSAGE TERRAIN_CHECK PACKING - -#define MAVLINK_MSG_ID_TERRAIN_CHECK 135 - - -typedef struct __mavlink_terrain_check_t { - int32_t lat; /*< [degE7] Latitude*/ - int32_t lon; /*< [degE7] Longitude*/ -} mavlink_terrain_check_t; - -#define MAVLINK_MSG_ID_TERRAIN_CHECK_LEN 8 -#define MAVLINK_MSG_ID_TERRAIN_CHECK_MIN_LEN 8 -#define MAVLINK_MSG_ID_135_LEN 8 -#define MAVLINK_MSG_ID_135_MIN_LEN 8 - -#define MAVLINK_MSG_ID_TERRAIN_CHECK_CRC 203 -#define MAVLINK_MSG_ID_135_CRC 203 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_TERRAIN_CHECK { \ - 135, \ - "TERRAIN_CHECK", \ - 2, \ - { { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_terrain_check_t, lat) }, \ - { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_terrain_check_t, lon) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_TERRAIN_CHECK { \ - "TERRAIN_CHECK", \ - 2, \ - { { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_terrain_check_t, lat) }, \ - { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_terrain_check_t, lon) }, \ - } \ -} -#endif - -/** - * @brief Pack a terrain_check message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param lat [degE7] Latitude - * @param lon [degE7] Longitude - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_terrain_check_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - int32_t lat, int32_t lon) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_TERRAIN_CHECK_LEN]; - _mav_put_int32_t(buf, 0, lat); - _mav_put_int32_t(buf, 4, lon); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_TERRAIN_CHECK_LEN); -#else - mavlink_terrain_check_t packet; - packet.lat = lat; - packet.lon = lon; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_TERRAIN_CHECK_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_TERRAIN_CHECK; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_TERRAIN_CHECK_MIN_LEN, MAVLINK_MSG_ID_TERRAIN_CHECK_LEN, MAVLINK_MSG_ID_TERRAIN_CHECK_CRC); -} - -/** - * @brief Pack a terrain_check message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param lat [degE7] Latitude - * @param lon [degE7] Longitude - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_terrain_check_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - int32_t lat,int32_t lon) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_TERRAIN_CHECK_LEN]; - _mav_put_int32_t(buf, 0, lat); - _mav_put_int32_t(buf, 4, lon); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_TERRAIN_CHECK_LEN); -#else - mavlink_terrain_check_t packet; - packet.lat = lat; - packet.lon = lon; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_TERRAIN_CHECK_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_TERRAIN_CHECK; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_TERRAIN_CHECK_MIN_LEN, MAVLINK_MSG_ID_TERRAIN_CHECK_LEN, MAVLINK_MSG_ID_TERRAIN_CHECK_CRC); -} - -/** - * @brief Encode a terrain_check struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param terrain_check C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_terrain_check_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_terrain_check_t* terrain_check) -{ - return mavlink_msg_terrain_check_pack(system_id, component_id, msg, terrain_check->lat, terrain_check->lon); -} - -/** - * @brief Encode a terrain_check struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param terrain_check C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_terrain_check_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_terrain_check_t* terrain_check) -{ - return mavlink_msg_terrain_check_pack_chan(system_id, component_id, chan, msg, terrain_check->lat, terrain_check->lon); -} - -/** - * @brief Send a terrain_check message - * @param chan MAVLink channel to send the message - * - * @param lat [degE7] Latitude - * @param lon [degE7] Longitude - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_terrain_check_send(mavlink_channel_t chan, int32_t lat, int32_t lon) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_TERRAIN_CHECK_LEN]; - _mav_put_int32_t(buf, 0, lat); - _mav_put_int32_t(buf, 4, lon); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_CHECK, buf, MAVLINK_MSG_ID_TERRAIN_CHECK_MIN_LEN, MAVLINK_MSG_ID_TERRAIN_CHECK_LEN, MAVLINK_MSG_ID_TERRAIN_CHECK_CRC); -#else - mavlink_terrain_check_t packet; - packet.lat = lat; - packet.lon = lon; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_CHECK, (const char *)&packet, MAVLINK_MSG_ID_TERRAIN_CHECK_MIN_LEN, MAVLINK_MSG_ID_TERRAIN_CHECK_LEN, MAVLINK_MSG_ID_TERRAIN_CHECK_CRC); -#endif -} - -/** - * @brief Send a terrain_check message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_terrain_check_send_struct(mavlink_channel_t chan, const mavlink_terrain_check_t* terrain_check) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_terrain_check_send(chan, terrain_check->lat, terrain_check->lon); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_CHECK, (const char *)terrain_check, MAVLINK_MSG_ID_TERRAIN_CHECK_MIN_LEN, MAVLINK_MSG_ID_TERRAIN_CHECK_LEN, MAVLINK_MSG_ID_TERRAIN_CHECK_CRC); -#endif -} - -#if MAVLINK_MSG_ID_TERRAIN_CHECK_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_terrain_check_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, int32_t lat, int32_t lon) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_int32_t(buf, 0, lat); - _mav_put_int32_t(buf, 4, lon); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_CHECK, buf, MAVLINK_MSG_ID_TERRAIN_CHECK_MIN_LEN, MAVLINK_MSG_ID_TERRAIN_CHECK_LEN, MAVLINK_MSG_ID_TERRAIN_CHECK_CRC); -#else - mavlink_terrain_check_t *packet = (mavlink_terrain_check_t *)msgbuf; - packet->lat = lat; - packet->lon = lon; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_CHECK, (const char *)packet, MAVLINK_MSG_ID_TERRAIN_CHECK_MIN_LEN, MAVLINK_MSG_ID_TERRAIN_CHECK_LEN, MAVLINK_MSG_ID_TERRAIN_CHECK_CRC); -#endif -} -#endif - -#endif - -// MESSAGE TERRAIN_CHECK UNPACKING - - -/** - * @brief Get field lat from terrain_check message - * - * @return [degE7] Latitude - */ -static inline int32_t mavlink_msg_terrain_check_get_lat(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 0); -} - -/** - * @brief Get field lon from terrain_check message - * - * @return [degE7] Longitude - */ -static inline int32_t mavlink_msg_terrain_check_get_lon(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 4); -} - -/** - * @brief Decode a terrain_check message into a struct - * - * @param msg The message to decode - * @param terrain_check C-struct to decode the message contents into - */ -static inline void mavlink_msg_terrain_check_decode(const mavlink_message_t* msg, mavlink_terrain_check_t* terrain_check) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - terrain_check->lat = mavlink_msg_terrain_check_get_lat(msg); - terrain_check->lon = mavlink_msg_terrain_check_get_lon(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_TERRAIN_CHECK_LEN? msg->len : MAVLINK_MSG_ID_TERRAIN_CHECK_LEN; - memset(terrain_check, 0, MAVLINK_MSG_ID_TERRAIN_CHECK_LEN); - memcpy(terrain_check, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_terrain_data.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_terrain_data.h deleted file mode 100644 index ca674511..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_terrain_data.h +++ /dev/null @@ -1,305 +0,0 @@ -#pragma once -// MESSAGE TERRAIN_DATA PACKING - -#define MAVLINK_MSG_ID_TERRAIN_DATA 134 - - -typedef struct __mavlink_terrain_data_t { - int32_t lat; /*< [degE7] Latitude of SW corner of first grid*/ - int32_t lon; /*< [degE7] Longitude of SW corner of first grid*/ - uint16_t grid_spacing; /*< [m] Grid spacing*/ - int16_t data[16]; /*< [m] Terrain data MSL*/ - uint8_t gridbit; /*< bit within the terrain request mask*/ -} mavlink_terrain_data_t; - -#define MAVLINK_MSG_ID_TERRAIN_DATA_LEN 43 -#define MAVLINK_MSG_ID_TERRAIN_DATA_MIN_LEN 43 -#define MAVLINK_MSG_ID_134_LEN 43 -#define MAVLINK_MSG_ID_134_MIN_LEN 43 - -#define MAVLINK_MSG_ID_TERRAIN_DATA_CRC 229 -#define MAVLINK_MSG_ID_134_CRC 229 - -#define MAVLINK_MSG_TERRAIN_DATA_FIELD_DATA_LEN 16 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_TERRAIN_DATA { \ - 134, \ - "TERRAIN_DATA", \ - 5, \ - { { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_terrain_data_t, lat) }, \ - { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_terrain_data_t, lon) }, \ - { "grid_spacing", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_terrain_data_t, grid_spacing) }, \ - { "gridbit", NULL, MAVLINK_TYPE_UINT8_T, 0, 42, offsetof(mavlink_terrain_data_t, gridbit) }, \ - { "data", NULL, MAVLINK_TYPE_INT16_T, 16, 10, offsetof(mavlink_terrain_data_t, data) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_TERRAIN_DATA { \ - "TERRAIN_DATA", \ - 5, \ - { { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_terrain_data_t, lat) }, \ - { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_terrain_data_t, lon) }, \ - { "grid_spacing", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_terrain_data_t, grid_spacing) }, \ - { "gridbit", NULL, MAVLINK_TYPE_UINT8_T, 0, 42, offsetof(mavlink_terrain_data_t, gridbit) }, \ - { "data", NULL, MAVLINK_TYPE_INT16_T, 16, 10, offsetof(mavlink_terrain_data_t, data) }, \ - } \ -} -#endif - -/** - * @brief Pack a terrain_data message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param lat [degE7] Latitude of SW corner of first grid - * @param lon [degE7] Longitude of SW corner of first grid - * @param grid_spacing [m] Grid spacing - * @param gridbit bit within the terrain request mask - * @param data [m] Terrain data MSL - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_terrain_data_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - int32_t lat, int32_t lon, uint16_t grid_spacing, uint8_t gridbit, const int16_t *data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_TERRAIN_DATA_LEN]; - _mav_put_int32_t(buf, 0, lat); - _mav_put_int32_t(buf, 4, lon); - _mav_put_uint16_t(buf, 8, grid_spacing); - _mav_put_uint8_t(buf, 42, gridbit); - _mav_put_int16_t_array(buf, 10, data, 16); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_TERRAIN_DATA_LEN); -#else - mavlink_terrain_data_t packet; - packet.lat = lat; - packet.lon = lon; - packet.grid_spacing = grid_spacing; - packet.gridbit = gridbit; - mav_array_memcpy(packet.data, data, sizeof(int16_t)*16); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_TERRAIN_DATA_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_TERRAIN_DATA; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_TERRAIN_DATA_MIN_LEN, MAVLINK_MSG_ID_TERRAIN_DATA_LEN, MAVLINK_MSG_ID_TERRAIN_DATA_CRC); -} - -/** - * @brief Pack a terrain_data message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param lat [degE7] Latitude of SW corner of first grid - * @param lon [degE7] Longitude of SW corner of first grid - * @param grid_spacing [m] Grid spacing - * @param gridbit bit within the terrain request mask - * @param data [m] Terrain data MSL - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_terrain_data_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - int32_t lat,int32_t lon,uint16_t grid_spacing,uint8_t gridbit,const int16_t *data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_TERRAIN_DATA_LEN]; - _mav_put_int32_t(buf, 0, lat); - _mav_put_int32_t(buf, 4, lon); - _mav_put_uint16_t(buf, 8, grid_spacing); - _mav_put_uint8_t(buf, 42, gridbit); - _mav_put_int16_t_array(buf, 10, data, 16); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_TERRAIN_DATA_LEN); -#else - mavlink_terrain_data_t packet; - packet.lat = lat; - packet.lon = lon; - packet.grid_spacing = grid_spacing; - packet.gridbit = gridbit; - mav_array_memcpy(packet.data, data, sizeof(int16_t)*16); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_TERRAIN_DATA_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_TERRAIN_DATA; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_TERRAIN_DATA_MIN_LEN, MAVLINK_MSG_ID_TERRAIN_DATA_LEN, MAVLINK_MSG_ID_TERRAIN_DATA_CRC); -} - -/** - * @brief Encode a terrain_data struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param terrain_data C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_terrain_data_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_terrain_data_t* terrain_data) -{ - return mavlink_msg_terrain_data_pack(system_id, component_id, msg, terrain_data->lat, terrain_data->lon, terrain_data->grid_spacing, terrain_data->gridbit, terrain_data->data); -} - -/** - * @brief Encode a terrain_data struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param terrain_data C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_terrain_data_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_terrain_data_t* terrain_data) -{ - return mavlink_msg_terrain_data_pack_chan(system_id, component_id, chan, msg, terrain_data->lat, terrain_data->lon, terrain_data->grid_spacing, terrain_data->gridbit, terrain_data->data); -} - -/** - * @brief Send a terrain_data message - * @param chan MAVLink channel to send the message - * - * @param lat [degE7] Latitude of SW corner of first grid - * @param lon [degE7] Longitude of SW corner of first grid - * @param grid_spacing [m] Grid spacing - * @param gridbit bit within the terrain request mask - * @param data [m] Terrain data MSL - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_terrain_data_send(mavlink_channel_t chan, int32_t lat, int32_t lon, uint16_t grid_spacing, uint8_t gridbit, const int16_t *data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_TERRAIN_DATA_LEN]; - _mav_put_int32_t(buf, 0, lat); - _mav_put_int32_t(buf, 4, lon); - _mav_put_uint16_t(buf, 8, grid_spacing); - _mav_put_uint8_t(buf, 42, gridbit); - _mav_put_int16_t_array(buf, 10, data, 16); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_DATA, buf, MAVLINK_MSG_ID_TERRAIN_DATA_MIN_LEN, MAVLINK_MSG_ID_TERRAIN_DATA_LEN, MAVLINK_MSG_ID_TERRAIN_DATA_CRC); -#else - mavlink_terrain_data_t packet; - packet.lat = lat; - packet.lon = lon; - packet.grid_spacing = grid_spacing; - packet.gridbit = gridbit; - mav_array_memcpy(packet.data, data, sizeof(int16_t)*16); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_DATA, (const char *)&packet, MAVLINK_MSG_ID_TERRAIN_DATA_MIN_LEN, MAVLINK_MSG_ID_TERRAIN_DATA_LEN, MAVLINK_MSG_ID_TERRAIN_DATA_CRC); -#endif -} - -/** - * @brief Send a terrain_data message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_terrain_data_send_struct(mavlink_channel_t chan, const mavlink_terrain_data_t* terrain_data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_terrain_data_send(chan, terrain_data->lat, terrain_data->lon, terrain_data->grid_spacing, terrain_data->gridbit, terrain_data->data); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_DATA, (const char *)terrain_data, MAVLINK_MSG_ID_TERRAIN_DATA_MIN_LEN, MAVLINK_MSG_ID_TERRAIN_DATA_LEN, MAVLINK_MSG_ID_TERRAIN_DATA_CRC); -#endif -} - -#if MAVLINK_MSG_ID_TERRAIN_DATA_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_terrain_data_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, int32_t lat, int32_t lon, uint16_t grid_spacing, uint8_t gridbit, const int16_t *data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_int32_t(buf, 0, lat); - _mav_put_int32_t(buf, 4, lon); - _mav_put_uint16_t(buf, 8, grid_spacing); - _mav_put_uint8_t(buf, 42, gridbit); - _mav_put_int16_t_array(buf, 10, data, 16); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_DATA, buf, MAVLINK_MSG_ID_TERRAIN_DATA_MIN_LEN, MAVLINK_MSG_ID_TERRAIN_DATA_LEN, MAVLINK_MSG_ID_TERRAIN_DATA_CRC); -#else - mavlink_terrain_data_t *packet = (mavlink_terrain_data_t *)msgbuf; - packet->lat = lat; - packet->lon = lon; - packet->grid_spacing = grid_spacing; - packet->gridbit = gridbit; - mav_array_memcpy(packet->data, data, sizeof(int16_t)*16); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_DATA, (const char *)packet, MAVLINK_MSG_ID_TERRAIN_DATA_MIN_LEN, MAVLINK_MSG_ID_TERRAIN_DATA_LEN, MAVLINK_MSG_ID_TERRAIN_DATA_CRC); -#endif -} -#endif - -#endif - -// MESSAGE TERRAIN_DATA UNPACKING - - -/** - * @brief Get field lat from terrain_data message - * - * @return [degE7] Latitude of SW corner of first grid - */ -static inline int32_t mavlink_msg_terrain_data_get_lat(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 0); -} - -/** - * @brief Get field lon from terrain_data message - * - * @return [degE7] Longitude of SW corner of first grid - */ -static inline int32_t mavlink_msg_terrain_data_get_lon(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 4); -} - -/** - * @brief Get field grid_spacing from terrain_data message - * - * @return [m] Grid spacing - */ -static inline uint16_t mavlink_msg_terrain_data_get_grid_spacing(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 8); -} - -/** - * @brief Get field gridbit from terrain_data message - * - * @return bit within the terrain request mask - */ -static inline uint8_t mavlink_msg_terrain_data_get_gridbit(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 42); -} - -/** - * @brief Get field data from terrain_data message - * - * @return [m] Terrain data MSL - */ -static inline uint16_t mavlink_msg_terrain_data_get_data(const mavlink_message_t* msg, int16_t *data) -{ - return _MAV_RETURN_int16_t_array(msg, data, 16, 10); -} - -/** - * @brief Decode a terrain_data message into a struct - * - * @param msg The message to decode - * @param terrain_data C-struct to decode the message contents into - */ -static inline void mavlink_msg_terrain_data_decode(const mavlink_message_t* msg, mavlink_terrain_data_t* terrain_data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - terrain_data->lat = mavlink_msg_terrain_data_get_lat(msg); - terrain_data->lon = mavlink_msg_terrain_data_get_lon(msg); - terrain_data->grid_spacing = mavlink_msg_terrain_data_get_grid_spacing(msg); - mavlink_msg_terrain_data_get_data(msg, terrain_data->data); - terrain_data->gridbit = mavlink_msg_terrain_data_get_gridbit(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_TERRAIN_DATA_LEN? msg->len : MAVLINK_MSG_ID_TERRAIN_DATA_LEN; - memset(terrain_data, 0, MAVLINK_MSG_ID_TERRAIN_DATA_LEN); - memcpy(terrain_data, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_terrain_report.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_terrain_report.h deleted file mode 100644 index 92d57a4a..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_terrain_report.h +++ /dev/null @@ -1,363 +0,0 @@ -#pragma once -// MESSAGE TERRAIN_REPORT PACKING - -#define MAVLINK_MSG_ID_TERRAIN_REPORT 136 - - -typedef struct __mavlink_terrain_report_t { - int32_t lat; /*< [degE7] Latitude*/ - int32_t lon; /*< [degE7] Longitude*/ - float terrain_height; /*< [m] Terrain height MSL*/ - float current_height; /*< [m] Current vehicle height above lat/lon terrain height*/ - uint16_t spacing; /*< grid spacing (zero if terrain at this location unavailable)*/ - uint16_t pending; /*< Number of 4x4 terrain blocks waiting to be received or read from disk*/ - uint16_t loaded; /*< Number of 4x4 terrain blocks in memory*/ -} mavlink_terrain_report_t; - -#define MAVLINK_MSG_ID_TERRAIN_REPORT_LEN 22 -#define MAVLINK_MSG_ID_TERRAIN_REPORT_MIN_LEN 22 -#define MAVLINK_MSG_ID_136_LEN 22 -#define MAVLINK_MSG_ID_136_MIN_LEN 22 - -#define MAVLINK_MSG_ID_TERRAIN_REPORT_CRC 1 -#define MAVLINK_MSG_ID_136_CRC 1 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_TERRAIN_REPORT { \ - 136, \ - "TERRAIN_REPORT", \ - 7, \ - { { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_terrain_report_t, lat) }, \ - { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_terrain_report_t, lon) }, \ - { "spacing", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_terrain_report_t, spacing) }, \ - { "terrain_height", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_terrain_report_t, terrain_height) }, \ - { "current_height", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_terrain_report_t, current_height) }, \ - { "pending", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_terrain_report_t, pending) }, \ - { "loaded", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_terrain_report_t, loaded) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_TERRAIN_REPORT { \ - "TERRAIN_REPORT", \ - 7, \ - { { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_terrain_report_t, lat) }, \ - { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_terrain_report_t, lon) }, \ - { "spacing", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_terrain_report_t, spacing) }, \ - { "terrain_height", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_terrain_report_t, terrain_height) }, \ - { "current_height", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_terrain_report_t, current_height) }, \ - { "pending", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_terrain_report_t, pending) }, \ - { "loaded", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_terrain_report_t, loaded) }, \ - } \ -} -#endif - -/** - * @brief Pack a terrain_report message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param lat [degE7] Latitude - * @param lon [degE7] Longitude - * @param spacing grid spacing (zero if terrain at this location unavailable) - * @param terrain_height [m] Terrain height MSL - * @param current_height [m] Current vehicle height above lat/lon terrain height - * @param pending Number of 4x4 terrain blocks waiting to be received or read from disk - * @param loaded Number of 4x4 terrain blocks in memory - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_terrain_report_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - int32_t lat, int32_t lon, uint16_t spacing, float terrain_height, float current_height, uint16_t pending, uint16_t loaded) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_TERRAIN_REPORT_LEN]; - _mav_put_int32_t(buf, 0, lat); - _mav_put_int32_t(buf, 4, lon); - _mav_put_float(buf, 8, terrain_height); - _mav_put_float(buf, 12, current_height); - _mav_put_uint16_t(buf, 16, spacing); - _mav_put_uint16_t(buf, 18, pending); - _mav_put_uint16_t(buf, 20, loaded); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_TERRAIN_REPORT_LEN); -#else - mavlink_terrain_report_t packet; - packet.lat = lat; - packet.lon = lon; - packet.terrain_height = terrain_height; - packet.current_height = current_height; - packet.spacing = spacing; - packet.pending = pending; - packet.loaded = loaded; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_TERRAIN_REPORT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_TERRAIN_REPORT; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_TERRAIN_REPORT_MIN_LEN, MAVLINK_MSG_ID_TERRAIN_REPORT_LEN, MAVLINK_MSG_ID_TERRAIN_REPORT_CRC); -} - -/** - * @brief Pack a terrain_report message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param lat [degE7] Latitude - * @param lon [degE7] Longitude - * @param spacing grid spacing (zero if terrain at this location unavailable) - * @param terrain_height [m] Terrain height MSL - * @param current_height [m] Current vehicle height above lat/lon terrain height - * @param pending Number of 4x4 terrain blocks waiting to be received or read from disk - * @param loaded Number of 4x4 terrain blocks in memory - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_terrain_report_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - int32_t lat,int32_t lon,uint16_t spacing,float terrain_height,float current_height,uint16_t pending,uint16_t loaded) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_TERRAIN_REPORT_LEN]; - _mav_put_int32_t(buf, 0, lat); - _mav_put_int32_t(buf, 4, lon); - _mav_put_float(buf, 8, terrain_height); - _mav_put_float(buf, 12, current_height); - _mav_put_uint16_t(buf, 16, spacing); - _mav_put_uint16_t(buf, 18, pending); - _mav_put_uint16_t(buf, 20, loaded); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_TERRAIN_REPORT_LEN); -#else - mavlink_terrain_report_t packet; - packet.lat = lat; - packet.lon = lon; - packet.terrain_height = terrain_height; - packet.current_height = current_height; - packet.spacing = spacing; - packet.pending = pending; - packet.loaded = loaded; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_TERRAIN_REPORT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_TERRAIN_REPORT; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_TERRAIN_REPORT_MIN_LEN, MAVLINK_MSG_ID_TERRAIN_REPORT_LEN, MAVLINK_MSG_ID_TERRAIN_REPORT_CRC); -} - -/** - * @brief Encode a terrain_report struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param terrain_report C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_terrain_report_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_terrain_report_t* terrain_report) -{ - return mavlink_msg_terrain_report_pack(system_id, component_id, msg, terrain_report->lat, terrain_report->lon, terrain_report->spacing, terrain_report->terrain_height, terrain_report->current_height, terrain_report->pending, terrain_report->loaded); -} - -/** - * @brief Encode a terrain_report struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param terrain_report C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_terrain_report_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_terrain_report_t* terrain_report) -{ - return mavlink_msg_terrain_report_pack_chan(system_id, component_id, chan, msg, terrain_report->lat, terrain_report->lon, terrain_report->spacing, terrain_report->terrain_height, terrain_report->current_height, terrain_report->pending, terrain_report->loaded); -} - -/** - * @brief Send a terrain_report message - * @param chan MAVLink channel to send the message - * - * @param lat [degE7] Latitude - * @param lon [degE7] Longitude - * @param spacing grid spacing (zero if terrain at this location unavailable) - * @param terrain_height [m] Terrain height MSL - * @param current_height [m] Current vehicle height above lat/lon terrain height - * @param pending Number of 4x4 terrain blocks waiting to be received or read from disk - * @param loaded Number of 4x4 terrain blocks in memory - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_terrain_report_send(mavlink_channel_t chan, int32_t lat, int32_t lon, uint16_t spacing, float terrain_height, float current_height, uint16_t pending, uint16_t loaded) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_TERRAIN_REPORT_LEN]; - _mav_put_int32_t(buf, 0, lat); - _mav_put_int32_t(buf, 4, lon); - _mav_put_float(buf, 8, terrain_height); - _mav_put_float(buf, 12, current_height); - _mav_put_uint16_t(buf, 16, spacing); - _mav_put_uint16_t(buf, 18, pending); - _mav_put_uint16_t(buf, 20, loaded); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_REPORT, buf, MAVLINK_MSG_ID_TERRAIN_REPORT_MIN_LEN, MAVLINK_MSG_ID_TERRAIN_REPORT_LEN, MAVLINK_MSG_ID_TERRAIN_REPORT_CRC); -#else - mavlink_terrain_report_t packet; - packet.lat = lat; - packet.lon = lon; - packet.terrain_height = terrain_height; - packet.current_height = current_height; - packet.spacing = spacing; - packet.pending = pending; - packet.loaded = loaded; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_REPORT, (const char *)&packet, MAVLINK_MSG_ID_TERRAIN_REPORT_MIN_LEN, MAVLINK_MSG_ID_TERRAIN_REPORT_LEN, MAVLINK_MSG_ID_TERRAIN_REPORT_CRC); -#endif -} - -/** - * @brief Send a terrain_report message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_terrain_report_send_struct(mavlink_channel_t chan, const mavlink_terrain_report_t* terrain_report) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_terrain_report_send(chan, terrain_report->lat, terrain_report->lon, terrain_report->spacing, terrain_report->terrain_height, terrain_report->current_height, terrain_report->pending, terrain_report->loaded); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_REPORT, (const char *)terrain_report, MAVLINK_MSG_ID_TERRAIN_REPORT_MIN_LEN, MAVLINK_MSG_ID_TERRAIN_REPORT_LEN, MAVLINK_MSG_ID_TERRAIN_REPORT_CRC); -#endif -} - -#if MAVLINK_MSG_ID_TERRAIN_REPORT_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_terrain_report_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, int32_t lat, int32_t lon, uint16_t spacing, float terrain_height, float current_height, uint16_t pending, uint16_t loaded) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_int32_t(buf, 0, lat); - _mav_put_int32_t(buf, 4, lon); - _mav_put_float(buf, 8, terrain_height); - _mav_put_float(buf, 12, current_height); - _mav_put_uint16_t(buf, 16, spacing); - _mav_put_uint16_t(buf, 18, pending); - _mav_put_uint16_t(buf, 20, loaded); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_REPORT, buf, MAVLINK_MSG_ID_TERRAIN_REPORT_MIN_LEN, MAVLINK_MSG_ID_TERRAIN_REPORT_LEN, MAVLINK_MSG_ID_TERRAIN_REPORT_CRC); -#else - mavlink_terrain_report_t *packet = (mavlink_terrain_report_t *)msgbuf; - packet->lat = lat; - packet->lon = lon; - packet->terrain_height = terrain_height; - packet->current_height = current_height; - packet->spacing = spacing; - packet->pending = pending; - packet->loaded = loaded; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_REPORT, (const char *)packet, MAVLINK_MSG_ID_TERRAIN_REPORT_MIN_LEN, MAVLINK_MSG_ID_TERRAIN_REPORT_LEN, MAVLINK_MSG_ID_TERRAIN_REPORT_CRC); -#endif -} -#endif - -#endif - -// MESSAGE TERRAIN_REPORT UNPACKING - - -/** - * @brief Get field lat from terrain_report message - * - * @return [degE7] Latitude - */ -static inline int32_t mavlink_msg_terrain_report_get_lat(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 0); -} - -/** - * @brief Get field lon from terrain_report message - * - * @return [degE7] Longitude - */ -static inline int32_t mavlink_msg_terrain_report_get_lon(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 4); -} - -/** - * @brief Get field spacing from terrain_report message - * - * @return grid spacing (zero if terrain at this location unavailable) - */ -static inline uint16_t mavlink_msg_terrain_report_get_spacing(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 16); -} - -/** - * @brief Get field terrain_height from terrain_report message - * - * @return [m] Terrain height MSL - */ -static inline float mavlink_msg_terrain_report_get_terrain_height(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field current_height from terrain_report message - * - * @return [m] Current vehicle height above lat/lon terrain height - */ -static inline float mavlink_msg_terrain_report_get_current_height(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field pending from terrain_report message - * - * @return Number of 4x4 terrain blocks waiting to be received or read from disk - */ -static inline uint16_t mavlink_msg_terrain_report_get_pending(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 18); -} - -/** - * @brief Get field loaded from terrain_report message - * - * @return Number of 4x4 terrain blocks in memory - */ -static inline uint16_t mavlink_msg_terrain_report_get_loaded(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 20); -} - -/** - * @brief Decode a terrain_report message into a struct - * - * @param msg The message to decode - * @param terrain_report C-struct to decode the message contents into - */ -static inline void mavlink_msg_terrain_report_decode(const mavlink_message_t* msg, mavlink_terrain_report_t* terrain_report) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - terrain_report->lat = mavlink_msg_terrain_report_get_lat(msg); - terrain_report->lon = mavlink_msg_terrain_report_get_lon(msg); - terrain_report->terrain_height = mavlink_msg_terrain_report_get_terrain_height(msg); - terrain_report->current_height = mavlink_msg_terrain_report_get_current_height(msg); - terrain_report->spacing = mavlink_msg_terrain_report_get_spacing(msg); - terrain_report->pending = mavlink_msg_terrain_report_get_pending(msg); - terrain_report->loaded = mavlink_msg_terrain_report_get_loaded(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_TERRAIN_REPORT_LEN? msg->len : MAVLINK_MSG_ID_TERRAIN_REPORT_LEN; - memset(terrain_report, 0, MAVLINK_MSG_ID_TERRAIN_REPORT_LEN); - memcpy(terrain_report, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_terrain_request.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_terrain_request.h deleted file mode 100644 index a76cfdd3..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_terrain_request.h +++ /dev/null @@ -1,288 +0,0 @@ -#pragma once -// MESSAGE TERRAIN_REQUEST PACKING - -#define MAVLINK_MSG_ID_TERRAIN_REQUEST 133 - - -typedef struct __mavlink_terrain_request_t { - uint64_t mask; /*< Bitmask of requested 4x4 grids (row major 8x7 array of grids, 56 bits)*/ - int32_t lat; /*< [degE7] Latitude of SW corner of first grid*/ - int32_t lon; /*< [degE7] Longitude of SW corner of first grid*/ - uint16_t grid_spacing; /*< [m] Grid spacing*/ -} mavlink_terrain_request_t; - -#define MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN 18 -#define MAVLINK_MSG_ID_TERRAIN_REQUEST_MIN_LEN 18 -#define MAVLINK_MSG_ID_133_LEN 18 -#define MAVLINK_MSG_ID_133_MIN_LEN 18 - -#define MAVLINK_MSG_ID_TERRAIN_REQUEST_CRC 6 -#define MAVLINK_MSG_ID_133_CRC 6 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_TERRAIN_REQUEST { \ - 133, \ - "TERRAIN_REQUEST", \ - 4, \ - { { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_terrain_request_t, lat) }, \ - { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_terrain_request_t, lon) }, \ - { "grid_spacing", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_terrain_request_t, grid_spacing) }, \ - { "mask", "0x%07x", MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_terrain_request_t, mask) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_TERRAIN_REQUEST { \ - "TERRAIN_REQUEST", \ - 4, \ - { { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_terrain_request_t, lat) }, \ - { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_terrain_request_t, lon) }, \ - { "grid_spacing", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_terrain_request_t, grid_spacing) }, \ - { "mask", "0x%07x", MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_terrain_request_t, mask) }, \ - } \ -} -#endif - -/** - * @brief Pack a terrain_request message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param lat [degE7] Latitude of SW corner of first grid - * @param lon [degE7] Longitude of SW corner of first grid - * @param grid_spacing [m] Grid spacing - * @param mask Bitmask of requested 4x4 grids (row major 8x7 array of grids, 56 bits) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_terrain_request_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - int32_t lat, int32_t lon, uint16_t grid_spacing, uint64_t mask) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN]; - _mav_put_uint64_t(buf, 0, mask); - _mav_put_int32_t(buf, 8, lat); - _mav_put_int32_t(buf, 12, lon); - _mav_put_uint16_t(buf, 16, grid_spacing); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN); -#else - mavlink_terrain_request_t packet; - packet.mask = mask; - packet.lat = lat; - packet.lon = lon; - packet.grid_spacing = grid_spacing; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_TERRAIN_REQUEST; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_TERRAIN_REQUEST_MIN_LEN, MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN, MAVLINK_MSG_ID_TERRAIN_REQUEST_CRC); -} - -/** - * @brief Pack a terrain_request message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param lat [degE7] Latitude of SW corner of first grid - * @param lon [degE7] Longitude of SW corner of first grid - * @param grid_spacing [m] Grid spacing - * @param mask Bitmask of requested 4x4 grids (row major 8x7 array of grids, 56 bits) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_terrain_request_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - int32_t lat,int32_t lon,uint16_t grid_spacing,uint64_t mask) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN]; - _mav_put_uint64_t(buf, 0, mask); - _mav_put_int32_t(buf, 8, lat); - _mav_put_int32_t(buf, 12, lon); - _mav_put_uint16_t(buf, 16, grid_spacing); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN); -#else - mavlink_terrain_request_t packet; - packet.mask = mask; - packet.lat = lat; - packet.lon = lon; - packet.grid_spacing = grid_spacing; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_TERRAIN_REQUEST; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_TERRAIN_REQUEST_MIN_LEN, MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN, MAVLINK_MSG_ID_TERRAIN_REQUEST_CRC); -} - -/** - * @brief Encode a terrain_request struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param terrain_request C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_terrain_request_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_terrain_request_t* terrain_request) -{ - return mavlink_msg_terrain_request_pack(system_id, component_id, msg, terrain_request->lat, terrain_request->lon, terrain_request->grid_spacing, terrain_request->mask); -} - -/** - * @brief Encode a terrain_request struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param terrain_request C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_terrain_request_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_terrain_request_t* terrain_request) -{ - return mavlink_msg_terrain_request_pack_chan(system_id, component_id, chan, msg, terrain_request->lat, terrain_request->lon, terrain_request->grid_spacing, terrain_request->mask); -} - -/** - * @brief Send a terrain_request message - * @param chan MAVLink channel to send the message - * - * @param lat [degE7] Latitude of SW corner of first grid - * @param lon [degE7] Longitude of SW corner of first grid - * @param grid_spacing [m] Grid spacing - * @param mask Bitmask of requested 4x4 grids (row major 8x7 array of grids, 56 bits) - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_terrain_request_send(mavlink_channel_t chan, int32_t lat, int32_t lon, uint16_t grid_spacing, uint64_t mask) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN]; - _mav_put_uint64_t(buf, 0, mask); - _mav_put_int32_t(buf, 8, lat); - _mav_put_int32_t(buf, 12, lon); - _mav_put_uint16_t(buf, 16, grid_spacing); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_REQUEST, buf, MAVLINK_MSG_ID_TERRAIN_REQUEST_MIN_LEN, MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN, MAVLINK_MSG_ID_TERRAIN_REQUEST_CRC); -#else - mavlink_terrain_request_t packet; - packet.mask = mask; - packet.lat = lat; - packet.lon = lon; - packet.grid_spacing = grid_spacing; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_REQUEST, (const char *)&packet, MAVLINK_MSG_ID_TERRAIN_REQUEST_MIN_LEN, MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN, MAVLINK_MSG_ID_TERRAIN_REQUEST_CRC); -#endif -} - -/** - * @brief Send a terrain_request message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_terrain_request_send_struct(mavlink_channel_t chan, const mavlink_terrain_request_t* terrain_request) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_terrain_request_send(chan, terrain_request->lat, terrain_request->lon, terrain_request->grid_spacing, terrain_request->mask); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_REQUEST, (const char *)terrain_request, MAVLINK_MSG_ID_TERRAIN_REQUEST_MIN_LEN, MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN, MAVLINK_MSG_ID_TERRAIN_REQUEST_CRC); -#endif -} - -#if MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_terrain_request_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, int32_t lat, int32_t lon, uint16_t grid_spacing, uint64_t mask) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, mask); - _mav_put_int32_t(buf, 8, lat); - _mav_put_int32_t(buf, 12, lon); - _mav_put_uint16_t(buf, 16, grid_spacing); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_REQUEST, buf, MAVLINK_MSG_ID_TERRAIN_REQUEST_MIN_LEN, MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN, MAVLINK_MSG_ID_TERRAIN_REQUEST_CRC); -#else - mavlink_terrain_request_t *packet = (mavlink_terrain_request_t *)msgbuf; - packet->mask = mask; - packet->lat = lat; - packet->lon = lon; - packet->grid_spacing = grid_spacing; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_REQUEST, (const char *)packet, MAVLINK_MSG_ID_TERRAIN_REQUEST_MIN_LEN, MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN, MAVLINK_MSG_ID_TERRAIN_REQUEST_CRC); -#endif -} -#endif - -#endif - -// MESSAGE TERRAIN_REQUEST UNPACKING - - -/** - * @brief Get field lat from terrain_request message - * - * @return [degE7] Latitude of SW corner of first grid - */ -static inline int32_t mavlink_msg_terrain_request_get_lat(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 8); -} - -/** - * @brief Get field lon from terrain_request message - * - * @return [degE7] Longitude of SW corner of first grid - */ -static inline int32_t mavlink_msg_terrain_request_get_lon(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 12); -} - -/** - * @brief Get field grid_spacing from terrain_request message - * - * @return [m] Grid spacing - */ -static inline uint16_t mavlink_msg_terrain_request_get_grid_spacing(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 16); -} - -/** - * @brief Get field mask from terrain_request message - * - * @return Bitmask of requested 4x4 grids (row major 8x7 array of grids, 56 bits) - */ -static inline uint64_t mavlink_msg_terrain_request_get_mask(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Decode a terrain_request message into a struct - * - * @param msg The message to decode - * @param terrain_request C-struct to decode the message contents into - */ -static inline void mavlink_msg_terrain_request_decode(const mavlink_message_t* msg, mavlink_terrain_request_t* terrain_request) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - terrain_request->mask = mavlink_msg_terrain_request_get_mask(msg); - terrain_request->lat = mavlink_msg_terrain_request_get_lat(msg); - terrain_request->lon = mavlink_msg_terrain_request_get_lon(msg); - terrain_request->grid_spacing = mavlink_msg_terrain_request_get_grid_spacing(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN? msg->len : MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN; - memset(terrain_request, 0, MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN); - memcpy(terrain_request, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_time_estimate_to_target.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_time_estimate_to_target.h deleted file mode 100644 index dd69e4cc..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_time_estimate_to_target.h +++ /dev/null @@ -1,313 +0,0 @@ -#pragma once -// MESSAGE TIME_ESTIMATE_TO_TARGET PACKING - -#define MAVLINK_MSG_ID_TIME_ESTIMATE_TO_TARGET 380 - - -typedef struct __mavlink_time_estimate_to_target_t { - int32_t safe_return; /*< [s] Estimated time to complete the vehicle's configured "safe return" action from its current position (e.g. RTL, Smart RTL, etc.). -1 indicates that the vehicle is landed, or that no time estimate available.*/ - int32_t land; /*< [s] Estimated time for vehicle to complete the LAND action from its current position. -1 indicates that the vehicle is landed, or that no time estimate available.*/ - int32_t mission_next_item; /*< [s] Estimated time for reaching/completing the currently active mission item. -1 means no time estimate available.*/ - int32_t mission_end; /*< [s] Estimated time for completing the current mission. -1 means no mission active and/or no estimate available.*/ - int32_t commanded_action; /*< [s] Estimated time for completing the current commanded action (i.e. Go To, Takeoff, Land, etc.). -1 means no action active and/or no estimate available.*/ -} mavlink_time_estimate_to_target_t; - -#define MAVLINK_MSG_ID_TIME_ESTIMATE_TO_TARGET_LEN 20 -#define MAVLINK_MSG_ID_TIME_ESTIMATE_TO_TARGET_MIN_LEN 20 -#define MAVLINK_MSG_ID_380_LEN 20 -#define MAVLINK_MSG_ID_380_MIN_LEN 20 - -#define MAVLINK_MSG_ID_TIME_ESTIMATE_TO_TARGET_CRC 232 -#define MAVLINK_MSG_ID_380_CRC 232 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_TIME_ESTIMATE_TO_TARGET { \ - 380, \ - "TIME_ESTIMATE_TO_TARGET", \ - 5, \ - { { "safe_return", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_time_estimate_to_target_t, safe_return) }, \ - { "land", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_time_estimate_to_target_t, land) }, \ - { "mission_next_item", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_time_estimate_to_target_t, mission_next_item) }, \ - { "mission_end", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_time_estimate_to_target_t, mission_end) }, \ - { "commanded_action", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_time_estimate_to_target_t, commanded_action) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_TIME_ESTIMATE_TO_TARGET { \ - "TIME_ESTIMATE_TO_TARGET", \ - 5, \ - { { "safe_return", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_time_estimate_to_target_t, safe_return) }, \ - { "land", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_time_estimate_to_target_t, land) }, \ - { "mission_next_item", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_time_estimate_to_target_t, mission_next_item) }, \ - { "mission_end", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_time_estimate_to_target_t, mission_end) }, \ - { "commanded_action", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_time_estimate_to_target_t, commanded_action) }, \ - } \ -} -#endif - -/** - * @brief Pack a time_estimate_to_target message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param safe_return [s] Estimated time to complete the vehicle's configured "safe return" action from its current position (e.g. RTL, Smart RTL, etc.). -1 indicates that the vehicle is landed, or that no time estimate available. - * @param land [s] Estimated time for vehicle to complete the LAND action from its current position. -1 indicates that the vehicle is landed, or that no time estimate available. - * @param mission_next_item [s] Estimated time for reaching/completing the currently active mission item. -1 means no time estimate available. - * @param mission_end [s] Estimated time for completing the current mission. -1 means no mission active and/or no estimate available. - * @param commanded_action [s] Estimated time for completing the current commanded action (i.e. Go To, Takeoff, Land, etc.). -1 means no action active and/or no estimate available. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_time_estimate_to_target_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - int32_t safe_return, int32_t land, int32_t mission_next_item, int32_t mission_end, int32_t commanded_action) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_TIME_ESTIMATE_TO_TARGET_LEN]; - _mav_put_int32_t(buf, 0, safe_return); - _mav_put_int32_t(buf, 4, land); - _mav_put_int32_t(buf, 8, mission_next_item); - _mav_put_int32_t(buf, 12, mission_end); - _mav_put_int32_t(buf, 16, commanded_action); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_TIME_ESTIMATE_TO_TARGET_LEN); -#else - mavlink_time_estimate_to_target_t packet; - packet.safe_return = safe_return; - packet.land = land; - packet.mission_next_item = mission_next_item; - packet.mission_end = mission_end; - packet.commanded_action = commanded_action; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_TIME_ESTIMATE_TO_TARGET_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_TIME_ESTIMATE_TO_TARGET; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_TIME_ESTIMATE_TO_TARGET_MIN_LEN, MAVLINK_MSG_ID_TIME_ESTIMATE_TO_TARGET_LEN, MAVLINK_MSG_ID_TIME_ESTIMATE_TO_TARGET_CRC); -} - -/** - * @brief Pack a time_estimate_to_target message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param safe_return [s] Estimated time to complete the vehicle's configured "safe return" action from its current position (e.g. RTL, Smart RTL, etc.). -1 indicates that the vehicle is landed, or that no time estimate available. - * @param land [s] Estimated time for vehicle to complete the LAND action from its current position. -1 indicates that the vehicle is landed, or that no time estimate available. - * @param mission_next_item [s] Estimated time for reaching/completing the currently active mission item. -1 means no time estimate available. - * @param mission_end [s] Estimated time for completing the current mission. -1 means no mission active and/or no estimate available. - * @param commanded_action [s] Estimated time for completing the current commanded action (i.e. Go To, Takeoff, Land, etc.). -1 means no action active and/or no estimate available. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_time_estimate_to_target_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - int32_t safe_return,int32_t land,int32_t mission_next_item,int32_t mission_end,int32_t commanded_action) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_TIME_ESTIMATE_TO_TARGET_LEN]; - _mav_put_int32_t(buf, 0, safe_return); - _mav_put_int32_t(buf, 4, land); - _mav_put_int32_t(buf, 8, mission_next_item); - _mav_put_int32_t(buf, 12, mission_end); - _mav_put_int32_t(buf, 16, commanded_action); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_TIME_ESTIMATE_TO_TARGET_LEN); -#else - mavlink_time_estimate_to_target_t packet; - packet.safe_return = safe_return; - packet.land = land; - packet.mission_next_item = mission_next_item; - packet.mission_end = mission_end; - packet.commanded_action = commanded_action; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_TIME_ESTIMATE_TO_TARGET_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_TIME_ESTIMATE_TO_TARGET; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_TIME_ESTIMATE_TO_TARGET_MIN_LEN, MAVLINK_MSG_ID_TIME_ESTIMATE_TO_TARGET_LEN, MAVLINK_MSG_ID_TIME_ESTIMATE_TO_TARGET_CRC); -} - -/** - * @brief Encode a time_estimate_to_target struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param time_estimate_to_target C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_time_estimate_to_target_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_time_estimate_to_target_t* time_estimate_to_target) -{ - return mavlink_msg_time_estimate_to_target_pack(system_id, component_id, msg, time_estimate_to_target->safe_return, time_estimate_to_target->land, time_estimate_to_target->mission_next_item, time_estimate_to_target->mission_end, time_estimate_to_target->commanded_action); -} - -/** - * @brief Encode a time_estimate_to_target struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_estimate_to_target C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_time_estimate_to_target_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_time_estimate_to_target_t* time_estimate_to_target) -{ - return mavlink_msg_time_estimate_to_target_pack_chan(system_id, component_id, chan, msg, time_estimate_to_target->safe_return, time_estimate_to_target->land, time_estimate_to_target->mission_next_item, time_estimate_to_target->mission_end, time_estimate_to_target->commanded_action); -} - -/** - * @brief Send a time_estimate_to_target message - * @param chan MAVLink channel to send the message - * - * @param safe_return [s] Estimated time to complete the vehicle's configured "safe return" action from its current position (e.g. RTL, Smart RTL, etc.). -1 indicates that the vehicle is landed, or that no time estimate available. - * @param land [s] Estimated time for vehicle to complete the LAND action from its current position. -1 indicates that the vehicle is landed, or that no time estimate available. - * @param mission_next_item [s] Estimated time for reaching/completing the currently active mission item. -1 means no time estimate available. - * @param mission_end [s] Estimated time for completing the current mission. -1 means no mission active and/or no estimate available. - * @param commanded_action [s] Estimated time for completing the current commanded action (i.e. Go To, Takeoff, Land, etc.). -1 means no action active and/or no estimate available. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_time_estimate_to_target_send(mavlink_channel_t chan, int32_t safe_return, int32_t land, int32_t mission_next_item, int32_t mission_end, int32_t commanded_action) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_TIME_ESTIMATE_TO_TARGET_LEN]; - _mav_put_int32_t(buf, 0, safe_return); - _mav_put_int32_t(buf, 4, land); - _mav_put_int32_t(buf, 8, mission_next_item); - _mav_put_int32_t(buf, 12, mission_end); - _mav_put_int32_t(buf, 16, commanded_action); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TIME_ESTIMATE_TO_TARGET, buf, MAVLINK_MSG_ID_TIME_ESTIMATE_TO_TARGET_MIN_LEN, MAVLINK_MSG_ID_TIME_ESTIMATE_TO_TARGET_LEN, MAVLINK_MSG_ID_TIME_ESTIMATE_TO_TARGET_CRC); -#else - mavlink_time_estimate_to_target_t packet; - packet.safe_return = safe_return; - packet.land = land; - packet.mission_next_item = mission_next_item; - packet.mission_end = mission_end; - packet.commanded_action = commanded_action; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TIME_ESTIMATE_TO_TARGET, (const char *)&packet, MAVLINK_MSG_ID_TIME_ESTIMATE_TO_TARGET_MIN_LEN, MAVLINK_MSG_ID_TIME_ESTIMATE_TO_TARGET_LEN, MAVLINK_MSG_ID_TIME_ESTIMATE_TO_TARGET_CRC); -#endif -} - -/** - * @brief Send a time_estimate_to_target message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_time_estimate_to_target_send_struct(mavlink_channel_t chan, const mavlink_time_estimate_to_target_t* time_estimate_to_target) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_time_estimate_to_target_send(chan, time_estimate_to_target->safe_return, time_estimate_to_target->land, time_estimate_to_target->mission_next_item, time_estimate_to_target->mission_end, time_estimate_to_target->commanded_action); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TIME_ESTIMATE_TO_TARGET, (const char *)time_estimate_to_target, MAVLINK_MSG_ID_TIME_ESTIMATE_TO_TARGET_MIN_LEN, MAVLINK_MSG_ID_TIME_ESTIMATE_TO_TARGET_LEN, MAVLINK_MSG_ID_TIME_ESTIMATE_TO_TARGET_CRC); -#endif -} - -#if MAVLINK_MSG_ID_TIME_ESTIMATE_TO_TARGET_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_time_estimate_to_target_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, int32_t safe_return, int32_t land, int32_t mission_next_item, int32_t mission_end, int32_t commanded_action) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_int32_t(buf, 0, safe_return); - _mav_put_int32_t(buf, 4, land); - _mav_put_int32_t(buf, 8, mission_next_item); - _mav_put_int32_t(buf, 12, mission_end); - _mav_put_int32_t(buf, 16, commanded_action); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TIME_ESTIMATE_TO_TARGET, buf, MAVLINK_MSG_ID_TIME_ESTIMATE_TO_TARGET_MIN_LEN, MAVLINK_MSG_ID_TIME_ESTIMATE_TO_TARGET_LEN, MAVLINK_MSG_ID_TIME_ESTIMATE_TO_TARGET_CRC); -#else - mavlink_time_estimate_to_target_t *packet = (mavlink_time_estimate_to_target_t *)msgbuf; - packet->safe_return = safe_return; - packet->land = land; - packet->mission_next_item = mission_next_item; - packet->mission_end = mission_end; - packet->commanded_action = commanded_action; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TIME_ESTIMATE_TO_TARGET, (const char *)packet, MAVLINK_MSG_ID_TIME_ESTIMATE_TO_TARGET_MIN_LEN, MAVLINK_MSG_ID_TIME_ESTIMATE_TO_TARGET_LEN, MAVLINK_MSG_ID_TIME_ESTIMATE_TO_TARGET_CRC); -#endif -} -#endif - -#endif - -// MESSAGE TIME_ESTIMATE_TO_TARGET UNPACKING - - -/** - * @brief Get field safe_return from time_estimate_to_target message - * - * @return [s] Estimated time to complete the vehicle's configured "safe return" action from its current position (e.g. RTL, Smart RTL, etc.). -1 indicates that the vehicle is landed, or that no time estimate available. - */ -static inline int32_t mavlink_msg_time_estimate_to_target_get_safe_return(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 0); -} - -/** - * @brief Get field land from time_estimate_to_target message - * - * @return [s] Estimated time for vehicle to complete the LAND action from its current position. -1 indicates that the vehicle is landed, or that no time estimate available. - */ -static inline int32_t mavlink_msg_time_estimate_to_target_get_land(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 4); -} - -/** - * @brief Get field mission_next_item from time_estimate_to_target message - * - * @return [s] Estimated time for reaching/completing the currently active mission item. -1 means no time estimate available. - */ -static inline int32_t mavlink_msg_time_estimate_to_target_get_mission_next_item(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 8); -} - -/** - * @brief Get field mission_end from time_estimate_to_target message - * - * @return [s] Estimated time for completing the current mission. -1 means no mission active and/or no estimate available. - */ -static inline int32_t mavlink_msg_time_estimate_to_target_get_mission_end(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 12); -} - -/** - * @brief Get field commanded_action from time_estimate_to_target message - * - * @return [s] Estimated time for completing the current commanded action (i.e. Go To, Takeoff, Land, etc.). -1 means no action active and/or no estimate available. - */ -static inline int32_t mavlink_msg_time_estimate_to_target_get_commanded_action(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 16); -} - -/** - * @brief Decode a time_estimate_to_target message into a struct - * - * @param msg The message to decode - * @param time_estimate_to_target C-struct to decode the message contents into - */ -static inline void mavlink_msg_time_estimate_to_target_decode(const mavlink_message_t* msg, mavlink_time_estimate_to_target_t* time_estimate_to_target) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - time_estimate_to_target->safe_return = mavlink_msg_time_estimate_to_target_get_safe_return(msg); - time_estimate_to_target->land = mavlink_msg_time_estimate_to_target_get_land(msg); - time_estimate_to_target->mission_next_item = mavlink_msg_time_estimate_to_target_get_mission_next_item(msg); - time_estimate_to_target->mission_end = mavlink_msg_time_estimate_to_target_get_mission_end(msg); - time_estimate_to_target->commanded_action = mavlink_msg_time_estimate_to_target_get_commanded_action(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_TIME_ESTIMATE_TO_TARGET_LEN? msg->len : MAVLINK_MSG_ID_TIME_ESTIMATE_TO_TARGET_LEN; - memset(time_estimate_to_target, 0, MAVLINK_MSG_ID_TIME_ESTIMATE_TO_TARGET_LEN); - memcpy(time_estimate_to_target, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_timesync.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_timesync.h deleted file mode 100644 index 6f514ecd..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_timesync.h +++ /dev/null @@ -1,288 +0,0 @@ -#pragma once -// MESSAGE TIMESYNC PACKING - -#define MAVLINK_MSG_ID_TIMESYNC 111 - - -typedef struct __mavlink_timesync_t { - int64_t tc1; /*< [ns] Time sync timestamp 1. Syncing: 0. Responding: Timestamp of responding component.*/ - int64_t ts1; /*< [ns] Time sync timestamp 2. Timestamp of syncing component (mirrored in response).*/ - uint8_t target_system; /*< Target system id. Request: 0 (broadcast) or id of specific system. Response must contain system id of the requesting component.*/ - uint8_t target_component; /*< Target component id. Request: 0 (broadcast) or id of specific component. Response must contain component id of the requesting component.*/ -} mavlink_timesync_t; - -#define MAVLINK_MSG_ID_TIMESYNC_LEN 18 -#define MAVLINK_MSG_ID_TIMESYNC_MIN_LEN 16 -#define MAVLINK_MSG_ID_111_LEN 18 -#define MAVLINK_MSG_ID_111_MIN_LEN 16 - -#define MAVLINK_MSG_ID_TIMESYNC_CRC 34 -#define MAVLINK_MSG_ID_111_CRC 34 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_TIMESYNC { \ - 111, \ - "TIMESYNC", \ - 4, \ - { { "tc1", NULL, MAVLINK_TYPE_INT64_T, 0, 0, offsetof(mavlink_timesync_t, tc1) }, \ - { "ts1", NULL, MAVLINK_TYPE_INT64_T, 0, 8, offsetof(mavlink_timesync_t, ts1) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_timesync_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 17, offsetof(mavlink_timesync_t, target_component) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_TIMESYNC { \ - "TIMESYNC", \ - 4, \ - { { "tc1", NULL, MAVLINK_TYPE_INT64_T, 0, 0, offsetof(mavlink_timesync_t, tc1) }, \ - { "ts1", NULL, MAVLINK_TYPE_INT64_T, 0, 8, offsetof(mavlink_timesync_t, ts1) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_timesync_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 17, offsetof(mavlink_timesync_t, target_component) }, \ - } \ -} -#endif - -/** - * @brief Pack a timesync message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param tc1 [ns] Time sync timestamp 1. Syncing: 0. Responding: Timestamp of responding component. - * @param ts1 [ns] Time sync timestamp 2. Timestamp of syncing component (mirrored in response). - * @param target_system Target system id. Request: 0 (broadcast) or id of specific system. Response must contain system id of the requesting component. - * @param target_component Target component id. Request: 0 (broadcast) or id of specific component. Response must contain component id of the requesting component. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_timesync_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - int64_t tc1, int64_t ts1, uint8_t target_system, uint8_t target_component) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_TIMESYNC_LEN]; - _mav_put_int64_t(buf, 0, tc1); - _mav_put_int64_t(buf, 8, ts1); - _mav_put_uint8_t(buf, 16, target_system); - _mav_put_uint8_t(buf, 17, target_component); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_TIMESYNC_LEN); -#else - mavlink_timesync_t packet; - packet.tc1 = tc1; - packet.ts1 = ts1; - packet.target_system = target_system; - packet.target_component = target_component; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_TIMESYNC_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_TIMESYNC; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_TIMESYNC_MIN_LEN, MAVLINK_MSG_ID_TIMESYNC_LEN, MAVLINK_MSG_ID_TIMESYNC_CRC); -} - -/** - * @brief Pack a timesync message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param tc1 [ns] Time sync timestamp 1. Syncing: 0. Responding: Timestamp of responding component. - * @param ts1 [ns] Time sync timestamp 2. Timestamp of syncing component (mirrored in response). - * @param target_system Target system id. Request: 0 (broadcast) or id of specific system. Response must contain system id of the requesting component. - * @param target_component Target component id. Request: 0 (broadcast) or id of specific component. Response must contain component id of the requesting component. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_timesync_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - int64_t tc1,int64_t ts1,uint8_t target_system,uint8_t target_component) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_TIMESYNC_LEN]; - _mav_put_int64_t(buf, 0, tc1); - _mav_put_int64_t(buf, 8, ts1); - _mav_put_uint8_t(buf, 16, target_system); - _mav_put_uint8_t(buf, 17, target_component); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_TIMESYNC_LEN); -#else - mavlink_timesync_t packet; - packet.tc1 = tc1; - packet.ts1 = ts1; - packet.target_system = target_system; - packet.target_component = target_component; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_TIMESYNC_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_TIMESYNC; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_TIMESYNC_MIN_LEN, MAVLINK_MSG_ID_TIMESYNC_LEN, MAVLINK_MSG_ID_TIMESYNC_CRC); -} - -/** - * @brief Encode a timesync struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param timesync C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_timesync_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_timesync_t* timesync) -{ - return mavlink_msg_timesync_pack(system_id, component_id, msg, timesync->tc1, timesync->ts1, timesync->target_system, timesync->target_component); -} - -/** - * @brief Encode a timesync struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param timesync C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_timesync_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_timesync_t* timesync) -{ - return mavlink_msg_timesync_pack_chan(system_id, component_id, chan, msg, timesync->tc1, timesync->ts1, timesync->target_system, timesync->target_component); -} - -/** - * @brief Send a timesync message - * @param chan MAVLink channel to send the message - * - * @param tc1 [ns] Time sync timestamp 1. Syncing: 0. Responding: Timestamp of responding component. - * @param ts1 [ns] Time sync timestamp 2. Timestamp of syncing component (mirrored in response). - * @param target_system Target system id. Request: 0 (broadcast) or id of specific system. Response must contain system id of the requesting component. - * @param target_component Target component id. Request: 0 (broadcast) or id of specific component. Response must contain component id of the requesting component. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_timesync_send(mavlink_channel_t chan, int64_t tc1, int64_t ts1, uint8_t target_system, uint8_t target_component) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_TIMESYNC_LEN]; - _mav_put_int64_t(buf, 0, tc1); - _mav_put_int64_t(buf, 8, ts1); - _mav_put_uint8_t(buf, 16, target_system); - _mav_put_uint8_t(buf, 17, target_component); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TIMESYNC, buf, MAVLINK_MSG_ID_TIMESYNC_MIN_LEN, MAVLINK_MSG_ID_TIMESYNC_LEN, MAVLINK_MSG_ID_TIMESYNC_CRC); -#else - mavlink_timesync_t packet; - packet.tc1 = tc1; - packet.ts1 = ts1; - packet.target_system = target_system; - packet.target_component = target_component; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TIMESYNC, (const char *)&packet, MAVLINK_MSG_ID_TIMESYNC_MIN_LEN, MAVLINK_MSG_ID_TIMESYNC_LEN, MAVLINK_MSG_ID_TIMESYNC_CRC); -#endif -} - -/** - * @brief Send a timesync message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_timesync_send_struct(mavlink_channel_t chan, const mavlink_timesync_t* timesync) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_timesync_send(chan, timesync->tc1, timesync->ts1, timesync->target_system, timesync->target_component); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TIMESYNC, (const char *)timesync, MAVLINK_MSG_ID_TIMESYNC_MIN_LEN, MAVLINK_MSG_ID_TIMESYNC_LEN, MAVLINK_MSG_ID_TIMESYNC_CRC); -#endif -} - -#if MAVLINK_MSG_ID_TIMESYNC_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_timesync_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, int64_t tc1, int64_t ts1, uint8_t target_system, uint8_t target_component) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_int64_t(buf, 0, tc1); - _mav_put_int64_t(buf, 8, ts1); - _mav_put_uint8_t(buf, 16, target_system); - _mav_put_uint8_t(buf, 17, target_component); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TIMESYNC, buf, MAVLINK_MSG_ID_TIMESYNC_MIN_LEN, MAVLINK_MSG_ID_TIMESYNC_LEN, MAVLINK_MSG_ID_TIMESYNC_CRC); -#else - mavlink_timesync_t *packet = (mavlink_timesync_t *)msgbuf; - packet->tc1 = tc1; - packet->ts1 = ts1; - packet->target_system = target_system; - packet->target_component = target_component; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TIMESYNC, (const char *)packet, MAVLINK_MSG_ID_TIMESYNC_MIN_LEN, MAVLINK_MSG_ID_TIMESYNC_LEN, MAVLINK_MSG_ID_TIMESYNC_CRC); -#endif -} -#endif - -#endif - -// MESSAGE TIMESYNC UNPACKING - - -/** - * @brief Get field tc1 from timesync message - * - * @return [ns] Time sync timestamp 1. Syncing: 0. Responding: Timestamp of responding component. - */ -static inline int64_t mavlink_msg_timesync_get_tc1(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int64_t(msg, 0); -} - -/** - * @brief Get field ts1 from timesync message - * - * @return [ns] Time sync timestamp 2. Timestamp of syncing component (mirrored in response). - */ -static inline int64_t mavlink_msg_timesync_get_ts1(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int64_t(msg, 8); -} - -/** - * @brief Get field target_system from timesync message - * - * @return Target system id. Request: 0 (broadcast) or id of specific system. Response must contain system id of the requesting component. - */ -static inline uint8_t mavlink_msg_timesync_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 16); -} - -/** - * @brief Get field target_component from timesync message - * - * @return Target component id. Request: 0 (broadcast) or id of specific component. Response must contain component id of the requesting component. - */ -static inline uint8_t mavlink_msg_timesync_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 17); -} - -/** - * @brief Decode a timesync message into a struct - * - * @param msg The message to decode - * @param timesync C-struct to decode the message contents into - */ -static inline void mavlink_msg_timesync_decode(const mavlink_message_t* msg, mavlink_timesync_t* timesync) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - timesync->tc1 = mavlink_msg_timesync_get_tc1(msg); - timesync->ts1 = mavlink_msg_timesync_get_ts1(msg); - timesync->target_system = mavlink_msg_timesync_get_target_system(msg); - timesync->target_component = mavlink_msg_timesync_get_target_component(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_TIMESYNC_LEN? msg->len : MAVLINK_MSG_ID_TIMESYNC_LEN; - memset(timesync, 0, MAVLINK_MSG_ID_TIMESYNC_LEN); - memcpy(timesync, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_trajectory_representation_bezier.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_trajectory_representation_bezier.h deleted file mode 100644 index 8764da35..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_trajectory_representation_bezier.h +++ /dev/null @@ -1,359 +0,0 @@ -#pragma once -// MESSAGE TRAJECTORY_REPRESENTATION_BEZIER PACKING - -#define MAVLINK_MSG_ID_TRAJECTORY_REPRESENTATION_BEZIER 333 - - -typedef struct __mavlink_trajectory_representation_bezier_t { - uint64_t time_usec; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/ - float pos_x[5]; /*< [m] X-coordinate of bezier control points. Set to NaN if not being used*/ - float pos_y[5]; /*< [m] Y-coordinate of bezier control points. Set to NaN if not being used*/ - float pos_z[5]; /*< [m] Z-coordinate of bezier control points. Set to NaN if not being used*/ - float delta[5]; /*< [s] Bezier time horizon. Set to NaN if velocity/acceleration should not be incorporated*/ - float pos_yaw[5]; /*< [rad] Yaw. Set to NaN for unchanged*/ - uint8_t valid_points; /*< Number of valid control points (up-to 5 points are possible)*/ -} mavlink_trajectory_representation_bezier_t; - -#define MAVLINK_MSG_ID_TRAJECTORY_REPRESENTATION_BEZIER_LEN 109 -#define MAVLINK_MSG_ID_TRAJECTORY_REPRESENTATION_BEZIER_MIN_LEN 109 -#define MAVLINK_MSG_ID_333_LEN 109 -#define MAVLINK_MSG_ID_333_MIN_LEN 109 - -#define MAVLINK_MSG_ID_TRAJECTORY_REPRESENTATION_BEZIER_CRC 231 -#define MAVLINK_MSG_ID_333_CRC 231 - -#define MAVLINK_MSG_TRAJECTORY_REPRESENTATION_BEZIER_FIELD_POS_X_LEN 5 -#define MAVLINK_MSG_TRAJECTORY_REPRESENTATION_BEZIER_FIELD_POS_Y_LEN 5 -#define MAVLINK_MSG_TRAJECTORY_REPRESENTATION_BEZIER_FIELD_POS_Z_LEN 5 -#define MAVLINK_MSG_TRAJECTORY_REPRESENTATION_BEZIER_FIELD_DELTA_LEN 5 -#define MAVLINK_MSG_TRAJECTORY_REPRESENTATION_BEZIER_FIELD_POS_YAW_LEN 5 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_TRAJECTORY_REPRESENTATION_BEZIER { \ - 333, \ - "TRAJECTORY_REPRESENTATION_BEZIER", \ - 7, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_trajectory_representation_bezier_t, time_usec) }, \ - { "valid_points", NULL, MAVLINK_TYPE_UINT8_T, 0, 108, offsetof(mavlink_trajectory_representation_bezier_t, valid_points) }, \ - { "pos_x", NULL, MAVLINK_TYPE_FLOAT, 5, 8, offsetof(mavlink_trajectory_representation_bezier_t, pos_x) }, \ - { "pos_y", NULL, MAVLINK_TYPE_FLOAT, 5, 28, offsetof(mavlink_trajectory_representation_bezier_t, pos_y) }, \ - { "pos_z", NULL, MAVLINK_TYPE_FLOAT, 5, 48, offsetof(mavlink_trajectory_representation_bezier_t, pos_z) }, \ - { "delta", NULL, MAVLINK_TYPE_FLOAT, 5, 68, offsetof(mavlink_trajectory_representation_bezier_t, delta) }, \ - { "pos_yaw", NULL, MAVLINK_TYPE_FLOAT, 5, 88, offsetof(mavlink_trajectory_representation_bezier_t, pos_yaw) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_TRAJECTORY_REPRESENTATION_BEZIER { \ - "TRAJECTORY_REPRESENTATION_BEZIER", \ - 7, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_trajectory_representation_bezier_t, time_usec) }, \ - { "valid_points", NULL, MAVLINK_TYPE_UINT8_T, 0, 108, offsetof(mavlink_trajectory_representation_bezier_t, valid_points) }, \ - { "pos_x", NULL, MAVLINK_TYPE_FLOAT, 5, 8, offsetof(mavlink_trajectory_representation_bezier_t, pos_x) }, \ - { "pos_y", NULL, MAVLINK_TYPE_FLOAT, 5, 28, offsetof(mavlink_trajectory_representation_bezier_t, pos_y) }, \ - { "pos_z", NULL, MAVLINK_TYPE_FLOAT, 5, 48, offsetof(mavlink_trajectory_representation_bezier_t, pos_z) }, \ - { "delta", NULL, MAVLINK_TYPE_FLOAT, 5, 68, offsetof(mavlink_trajectory_representation_bezier_t, delta) }, \ - { "pos_yaw", NULL, MAVLINK_TYPE_FLOAT, 5, 88, offsetof(mavlink_trajectory_representation_bezier_t, pos_yaw) }, \ - } \ -} -#endif - -/** - * @brief Pack a trajectory_representation_bezier message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @param valid_points Number of valid control points (up-to 5 points are possible) - * @param pos_x [m] X-coordinate of bezier control points. Set to NaN if not being used - * @param pos_y [m] Y-coordinate of bezier control points. Set to NaN if not being used - * @param pos_z [m] Z-coordinate of bezier control points. Set to NaN if not being used - * @param delta [s] Bezier time horizon. Set to NaN if velocity/acceleration should not be incorporated - * @param pos_yaw [rad] Yaw. Set to NaN for unchanged - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_trajectory_representation_bezier_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint64_t time_usec, uint8_t valid_points, const float *pos_x, const float *pos_y, const float *pos_z, const float *delta, const float *pos_yaw) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_TRAJECTORY_REPRESENTATION_BEZIER_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint8_t(buf, 108, valid_points); - _mav_put_float_array(buf, 8, pos_x, 5); - _mav_put_float_array(buf, 28, pos_y, 5); - _mav_put_float_array(buf, 48, pos_z, 5); - _mav_put_float_array(buf, 68, delta, 5); - _mav_put_float_array(buf, 88, pos_yaw, 5); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_TRAJECTORY_REPRESENTATION_BEZIER_LEN); -#else - mavlink_trajectory_representation_bezier_t packet; - packet.time_usec = time_usec; - packet.valid_points = valid_points; - mav_array_memcpy(packet.pos_x, pos_x, sizeof(float)*5); - mav_array_memcpy(packet.pos_y, pos_y, sizeof(float)*5); - mav_array_memcpy(packet.pos_z, pos_z, sizeof(float)*5); - mav_array_memcpy(packet.delta, delta, sizeof(float)*5); - mav_array_memcpy(packet.pos_yaw, pos_yaw, sizeof(float)*5); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_TRAJECTORY_REPRESENTATION_BEZIER_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_TRAJECTORY_REPRESENTATION_BEZIER; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_TRAJECTORY_REPRESENTATION_BEZIER_MIN_LEN, MAVLINK_MSG_ID_TRAJECTORY_REPRESENTATION_BEZIER_LEN, MAVLINK_MSG_ID_TRAJECTORY_REPRESENTATION_BEZIER_CRC); -} - -/** - * @brief Pack a trajectory_representation_bezier message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @param valid_points Number of valid control points (up-to 5 points are possible) - * @param pos_x [m] X-coordinate of bezier control points. Set to NaN if not being used - * @param pos_y [m] Y-coordinate of bezier control points. Set to NaN if not being used - * @param pos_z [m] Z-coordinate of bezier control points. Set to NaN if not being used - * @param delta [s] Bezier time horizon. Set to NaN if velocity/acceleration should not be incorporated - * @param pos_yaw [rad] Yaw. Set to NaN for unchanged - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_trajectory_representation_bezier_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint64_t time_usec,uint8_t valid_points,const float *pos_x,const float *pos_y,const float *pos_z,const float *delta,const float *pos_yaw) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_TRAJECTORY_REPRESENTATION_BEZIER_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint8_t(buf, 108, valid_points); - _mav_put_float_array(buf, 8, pos_x, 5); - _mav_put_float_array(buf, 28, pos_y, 5); - _mav_put_float_array(buf, 48, pos_z, 5); - _mav_put_float_array(buf, 68, delta, 5); - _mav_put_float_array(buf, 88, pos_yaw, 5); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_TRAJECTORY_REPRESENTATION_BEZIER_LEN); -#else - mavlink_trajectory_representation_bezier_t packet; - packet.time_usec = time_usec; - packet.valid_points = valid_points; - mav_array_memcpy(packet.pos_x, pos_x, sizeof(float)*5); - mav_array_memcpy(packet.pos_y, pos_y, sizeof(float)*5); - mav_array_memcpy(packet.pos_z, pos_z, sizeof(float)*5); - mav_array_memcpy(packet.delta, delta, sizeof(float)*5); - mav_array_memcpy(packet.pos_yaw, pos_yaw, sizeof(float)*5); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_TRAJECTORY_REPRESENTATION_BEZIER_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_TRAJECTORY_REPRESENTATION_BEZIER; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_TRAJECTORY_REPRESENTATION_BEZIER_MIN_LEN, MAVLINK_MSG_ID_TRAJECTORY_REPRESENTATION_BEZIER_LEN, MAVLINK_MSG_ID_TRAJECTORY_REPRESENTATION_BEZIER_CRC); -} - -/** - * @brief Encode a trajectory_representation_bezier struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param trajectory_representation_bezier C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_trajectory_representation_bezier_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_trajectory_representation_bezier_t* trajectory_representation_bezier) -{ - return mavlink_msg_trajectory_representation_bezier_pack(system_id, component_id, msg, trajectory_representation_bezier->time_usec, trajectory_representation_bezier->valid_points, trajectory_representation_bezier->pos_x, trajectory_representation_bezier->pos_y, trajectory_representation_bezier->pos_z, trajectory_representation_bezier->delta, trajectory_representation_bezier->pos_yaw); -} - -/** - * @brief Encode a trajectory_representation_bezier struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param trajectory_representation_bezier C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_trajectory_representation_bezier_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_trajectory_representation_bezier_t* trajectory_representation_bezier) -{ - return mavlink_msg_trajectory_representation_bezier_pack_chan(system_id, component_id, chan, msg, trajectory_representation_bezier->time_usec, trajectory_representation_bezier->valid_points, trajectory_representation_bezier->pos_x, trajectory_representation_bezier->pos_y, trajectory_representation_bezier->pos_z, trajectory_representation_bezier->delta, trajectory_representation_bezier->pos_yaw); -} - -/** - * @brief Send a trajectory_representation_bezier message - * @param chan MAVLink channel to send the message - * - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @param valid_points Number of valid control points (up-to 5 points are possible) - * @param pos_x [m] X-coordinate of bezier control points. Set to NaN if not being used - * @param pos_y [m] Y-coordinate of bezier control points. Set to NaN if not being used - * @param pos_z [m] Z-coordinate of bezier control points. Set to NaN if not being used - * @param delta [s] Bezier time horizon. Set to NaN if velocity/acceleration should not be incorporated - * @param pos_yaw [rad] Yaw. Set to NaN for unchanged - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_trajectory_representation_bezier_send(mavlink_channel_t chan, uint64_t time_usec, uint8_t valid_points, const float *pos_x, const float *pos_y, const float *pos_z, const float *delta, const float *pos_yaw) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_TRAJECTORY_REPRESENTATION_BEZIER_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint8_t(buf, 108, valid_points); - _mav_put_float_array(buf, 8, pos_x, 5); - _mav_put_float_array(buf, 28, pos_y, 5); - _mav_put_float_array(buf, 48, pos_z, 5); - _mav_put_float_array(buf, 68, delta, 5); - _mav_put_float_array(buf, 88, pos_yaw, 5); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TRAJECTORY_REPRESENTATION_BEZIER, buf, MAVLINK_MSG_ID_TRAJECTORY_REPRESENTATION_BEZIER_MIN_LEN, MAVLINK_MSG_ID_TRAJECTORY_REPRESENTATION_BEZIER_LEN, MAVLINK_MSG_ID_TRAJECTORY_REPRESENTATION_BEZIER_CRC); -#else - mavlink_trajectory_representation_bezier_t packet; - packet.time_usec = time_usec; - packet.valid_points = valid_points; - mav_array_memcpy(packet.pos_x, pos_x, sizeof(float)*5); - mav_array_memcpy(packet.pos_y, pos_y, sizeof(float)*5); - mav_array_memcpy(packet.pos_z, pos_z, sizeof(float)*5); - mav_array_memcpy(packet.delta, delta, sizeof(float)*5); - mav_array_memcpy(packet.pos_yaw, pos_yaw, sizeof(float)*5); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TRAJECTORY_REPRESENTATION_BEZIER, (const char *)&packet, MAVLINK_MSG_ID_TRAJECTORY_REPRESENTATION_BEZIER_MIN_LEN, MAVLINK_MSG_ID_TRAJECTORY_REPRESENTATION_BEZIER_LEN, MAVLINK_MSG_ID_TRAJECTORY_REPRESENTATION_BEZIER_CRC); -#endif -} - -/** - * @brief Send a trajectory_representation_bezier message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_trajectory_representation_bezier_send_struct(mavlink_channel_t chan, const mavlink_trajectory_representation_bezier_t* trajectory_representation_bezier) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_trajectory_representation_bezier_send(chan, trajectory_representation_bezier->time_usec, trajectory_representation_bezier->valid_points, trajectory_representation_bezier->pos_x, trajectory_representation_bezier->pos_y, trajectory_representation_bezier->pos_z, trajectory_representation_bezier->delta, trajectory_representation_bezier->pos_yaw); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TRAJECTORY_REPRESENTATION_BEZIER, (const char *)trajectory_representation_bezier, MAVLINK_MSG_ID_TRAJECTORY_REPRESENTATION_BEZIER_MIN_LEN, MAVLINK_MSG_ID_TRAJECTORY_REPRESENTATION_BEZIER_LEN, MAVLINK_MSG_ID_TRAJECTORY_REPRESENTATION_BEZIER_CRC); -#endif -} - -#if MAVLINK_MSG_ID_TRAJECTORY_REPRESENTATION_BEZIER_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_trajectory_representation_bezier_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, uint8_t valid_points, const float *pos_x, const float *pos_y, const float *pos_z, const float *delta, const float *pos_yaw) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint8_t(buf, 108, valid_points); - _mav_put_float_array(buf, 8, pos_x, 5); - _mav_put_float_array(buf, 28, pos_y, 5); - _mav_put_float_array(buf, 48, pos_z, 5); - _mav_put_float_array(buf, 68, delta, 5); - _mav_put_float_array(buf, 88, pos_yaw, 5); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TRAJECTORY_REPRESENTATION_BEZIER, buf, MAVLINK_MSG_ID_TRAJECTORY_REPRESENTATION_BEZIER_MIN_LEN, MAVLINK_MSG_ID_TRAJECTORY_REPRESENTATION_BEZIER_LEN, MAVLINK_MSG_ID_TRAJECTORY_REPRESENTATION_BEZIER_CRC); -#else - mavlink_trajectory_representation_bezier_t *packet = (mavlink_trajectory_representation_bezier_t *)msgbuf; - packet->time_usec = time_usec; - packet->valid_points = valid_points; - mav_array_memcpy(packet->pos_x, pos_x, sizeof(float)*5); - mav_array_memcpy(packet->pos_y, pos_y, sizeof(float)*5); - mav_array_memcpy(packet->pos_z, pos_z, sizeof(float)*5); - mav_array_memcpy(packet->delta, delta, sizeof(float)*5); - mav_array_memcpy(packet->pos_yaw, pos_yaw, sizeof(float)*5); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TRAJECTORY_REPRESENTATION_BEZIER, (const char *)packet, MAVLINK_MSG_ID_TRAJECTORY_REPRESENTATION_BEZIER_MIN_LEN, MAVLINK_MSG_ID_TRAJECTORY_REPRESENTATION_BEZIER_LEN, MAVLINK_MSG_ID_TRAJECTORY_REPRESENTATION_BEZIER_CRC); -#endif -} -#endif - -#endif - -// MESSAGE TRAJECTORY_REPRESENTATION_BEZIER UNPACKING - - -/** - * @brief Get field time_usec from trajectory_representation_bezier message - * - * @return [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - */ -static inline uint64_t mavlink_msg_trajectory_representation_bezier_get_time_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field valid_points from trajectory_representation_bezier message - * - * @return Number of valid control points (up-to 5 points are possible) - */ -static inline uint8_t mavlink_msg_trajectory_representation_bezier_get_valid_points(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 108); -} - -/** - * @brief Get field pos_x from trajectory_representation_bezier message - * - * @return [m] X-coordinate of bezier control points. Set to NaN if not being used - */ -static inline uint16_t mavlink_msg_trajectory_representation_bezier_get_pos_x(const mavlink_message_t* msg, float *pos_x) -{ - return _MAV_RETURN_float_array(msg, pos_x, 5, 8); -} - -/** - * @brief Get field pos_y from trajectory_representation_bezier message - * - * @return [m] Y-coordinate of bezier control points. Set to NaN if not being used - */ -static inline uint16_t mavlink_msg_trajectory_representation_bezier_get_pos_y(const mavlink_message_t* msg, float *pos_y) -{ - return _MAV_RETURN_float_array(msg, pos_y, 5, 28); -} - -/** - * @brief Get field pos_z from trajectory_representation_bezier message - * - * @return [m] Z-coordinate of bezier control points. Set to NaN if not being used - */ -static inline uint16_t mavlink_msg_trajectory_representation_bezier_get_pos_z(const mavlink_message_t* msg, float *pos_z) -{ - return _MAV_RETURN_float_array(msg, pos_z, 5, 48); -} - -/** - * @brief Get field delta from trajectory_representation_bezier message - * - * @return [s] Bezier time horizon. Set to NaN if velocity/acceleration should not be incorporated - */ -static inline uint16_t mavlink_msg_trajectory_representation_bezier_get_delta(const mavlink_message_t* msg, float *delta) -{ - return _MAV_RETURN_float_array(msg, delta, 5, 68); -} - -/** - * @brief Get field pos_yaw from trajectory_representation_bezier message - * - * @return [rad] Yaw. Set to NaN for unchanged - */ -static inline uint16_t mavlink_msg_trajectory_representation_bezier_get_pos_yaw(const mavlink_message_t* msg, float *pos_yaw) -{ - return _MAV_RETURN_float_array(msg, pos_yaw, 5, 88); -} - -/** - * @brief Decode a trajectory_representation_bezier message into a struct - * - * @param msg The message to decode - * @param trajectory_representation_bezier C-struct to decode the message contents into - */ -static inline void mavlink_msg_trajectory_representation_bezier_decode(const mavlink_message_t* msg, mavlink_trajectory_representation_bezier_t* trajectory_representation_bezier) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - trajectory_representation_bezier->time_usec = mavlink_msg_trajectory_representation_bezier_get_time_usec(msg); - mavlink_msg_trajectory_representation_bezier_get_pos_x(msg, trajectory_representation_bezier->pos_x); - mavlink_msg_trajectory_representation_bezier_get_pos_y(msg, trajectory_representation_bezier->pos_y); - mavlink_msg_trajectory_representation_bezier_get_pos_z(msg, trajectory_representation_bezier->pos_z); - mavlink_msg_trajectory_representation_bezier_get_delta(msg, trajectory_representation_bezier->delta); - mavlink_msg_trajectory_representation_bezier_get_pos_yaw(msg, trajectory_representation_bezier->pos_yaw); - trajectory_representation_bezier->valid_points = mavlink_msg_trajectory_representation_bezier_get_valid_points(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_TRAJECTORY_REPRESENTATION_BEZIER_LEN? msg->len : MAVLINK_MSG_ID_TRAJECTORY_REPRESENTATION_BEZIER_LEN; - memset(trajectory_representation_bezier, 0, MAVLINK_MSG_ID_TRAJECTORY_REPRESENTATION_BEZIER_LEN); - memcpy(trajectory_representation_bezier, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_trajectory_representation_waypoints.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_trajectory_representation_waypoints.h deleted file mode 100644 index 45798ccd..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_trajectory_representation_waypoints.h +++ /dev/null @@ -1,541 +0,0 @@ -#pragma once -// MESSAGE TRAJECTORY_REPRESENTATION_WAYPOINTS PACKING - -#define MAVLINK_MSG_ID_TRAJECTORY_REPRESENTATION_WAYPOINTS 332 - - -typedef struct __mavlink_trajectory_representation_waypoints_t { - uint64_t time_usec; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/ - float pos_x[5]; /*< [m] X-coordinate of waypoint, set to NaN if not being used*/ - float pos_y[5]; /*< [m] Y-coordinate of waypoint, set to NaN if not being used*/ - float pos_z[5]; /*< [m] Z-coordinate of waypoint, set to NaN if not being used*/ - float vel_x[5]; /*< [m/s] X-velocity of waypoint, set to NaN if not being used*/ - float vel_y[5]; /*< [m/s] Y-velocity of waypoint, set to NaN if not being used*/ - float vel_z[5]; /*< [m/s] Z-velocity of waypoint, set to NaN if not being used*/ - float acc_x[5]; /*< [m/s/s] X-acceleration of waypoint, set to NaN if not being used*/ - float acc_y[5]; /*< [m/s/s] Y-acceleration of waypoint, set to NaN if not being used*/ - float acc_z[5]; /*< [m/s/s] Z-acceleration of waypoint, set to NaN if not being used*/ - float pos_yaw[5]; /*< [rad] Yaw angle, set to NaN if not being used*/ - float vel_yaw[5]; /*< [rad/s] Yaw rate, set to NaN if not being used*/ - uint16_t command[5]; /*< MAV_CMD command id of waypoint, set to UINT16_MAX if not being used.*/ - uint8_t valid_points; /*< Number of valid points (up-to 5 waypoints are possible)*/ -} mavlink_trajectory_representation_waypoints_t; - -#define MAVLINK_MSG_ID_TRAJECTORY_REPRESENTATION_WAYPOINTS_LEN 239 -#define MAVLINK_MSG_ID_TRAJECTORY_REPRESENTATION_WAYPOINTS_MIN_LEN 239 -#define MAVLINK_MSG_ID_332_LEN 239 -#define MAVLINK_MSG_ID_332_MIN_LEN 239 - -#define MAVLINK_MSG_ID_TRAJECTORY_REPRESENTATION_WAYPOINTS_CRC 236 -#define MAVLINK_MSG_ID_332_CRC 236 - -#define MAVLINK_MSG_TRAJECTORY_REPRESENTATION_WAYPOINTS_FIELD_POS_X_LEN 5 -#define MAVLINK_MSG_TRAJECTORY_REPRESENTATION_WAYPOINTS_FIELD_POS_Y_LEN 5 -#define MAVLINK_MSG_TRAJECTORY_REPRESENTATION_WAYPOINTS_FIELD_POS_Z_LEN 5 -#define MAVLINK_MSG_TRAJECTORY_REPRESENTATION_WAYPOINTS_FIELD_VEL_X_LEN 5 -#define MAVLINK_MSG_TRAJECTORY_REPRESENTATION_WAYPOINTS_FIELD_VEL_Y_LEN 5 -#define MAVLINK_MSG_TRAJECTORY_REPRESENTATION_WAYPOINTS_FIELD_VEL_Z_LEN 5 -#define MAVLINK_MSG_TRAJECTORY_REPRESENTATION_WAYPOINTS_FIELD_ACC_X_LEN 5 -#define MAVLINK_MSG_TRAJECTORY_REPRESENTATION_WAYPOINTS_FIELD_ACC_Y_LEN 5 -#define MAVLINK_MSG_TRAJECTORY_REPRESENTATION_WAYPOINTS_FIELD_ACC_Z_LEN 5 -#define MAVLINK_MSG_TRAJECTORY_REPRESENTATION_WAYPOINTS_FIELD_POS_YAW_LEN 5 -#define MAVLINK_MSG_TRAJECTORY_REPRESENTATION_WAYPOINTS_FIELD_VEL_YAW_LEN 5 -#define MAVLINK_MSG_TRAJECTORY_REPRESENTATION_WAYPOINTS_FIELD_COMMAND_LEN 5 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_TRAJECTORY_REPRESENTATION_WAYPOINTS { \ - 332, \ - "TRAJECTORY_REPRESENTATION_WAYPOINTS", \ - 14, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_trajectory_representation_waypoints_t, time_usec) }, \ - { "valid_points", NULL, MAVLINK_TYPE_UINT8_T, 0, 238, offsetof(mavlink_trajectory_representation_waypoints_t, valid_points) }, \ - { "pos_x", NULL, MAVLINK_TYPE_FLOAT, 5, 8, offsetof(mavlink_trajectory_representation_waypoints_t, pos_x) }, \ - { "pos_y", NULL, MAVLINK_TYPE_FLOAT, 5, 28, offsetof(mavlink_trajectory_representation_waypoints_t, pos_y) }, \ - { "pos_z", NULL, MAVLINK_TYPE_FLOAT, 5, 48, offsetof(mavlink_trajectory_representation_waypoints_t, pos_z) }, \ - { "vel_x", NULL, MAVLINK_TYPE_FLOAT, 5, 68, offsetof(mavlink_trajectory_representation_waypoints_t, vel_x) }, \ - { "vel_y", NULL, MAVLINK_TYPE_FLOAT, 5, 88, offsetof(mavlink_trajectory_representation_waypoints_t, vel_y) }, \ - { "vel_z", NULL, MAVLINK_TYPE_FLOAT, 5, 108, offsetof(mavlink_trajectory_representation_waypoints_t, vel_z) }, \ - { "acc_x", NULL, MAVLINK_TYPE_FLOAT, 5, 128, offsetof(mavlink_trajectory_representation_waypoints_t, acc_x) }, \ - { "acc_y", NULL, MAVLINK_TYPE_FLOAT, 5, 148, offsetof(mavlink_trajectory_representation_waypoints_t, acc_y) }, \ - { "acc_z", NULL, MAVLINK_TYPE_FLOAT, 5, 168, offsetof(mavlink_trajectory_representation_waypoints_t, acc_z) }, \ - { "pos_yaw", NULL, MAVLINK_TYPE_FLOAT, 5, 188, offsetof(mavlink_trajectory_representation_waypoints_t, pos_yaw) }, \ - { "vel_yaw", NULL, MAVLINK_TYPE_FLOAT, 5, 208, offsetof(mavlink_trajectory_representation_waypoints_t, vel_yaw) }, \ - { "command", NULL, MAVLINK_TYPE_UINT16_T, 5, 228, offsetof(mavlink_trajectory_representation_waypoints_t, command) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_TRAJECTORY_REPRESENTATION_WAYPOINTS { \ - "TRAJECTORY_REPRESENTATION_WAYPOINTS", \ - 14, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_trajectory_representation_waypoints_t, time_usec) }, \ - { "valid_points", NULL, MAVLINK_TYPE_UINT8_T, 0, 238, offsetof(mavlink_trajectory_representation_waypoints_t, valid_points) }, \ - { "pos_x", NULL, MAVLINK_TYPE_FLOAT, 5, 8, offsetof(mavlink_trajectory_representation_waypoints_t, pos_x) }, \ - { "pos_y", NULL, MAVLINK_TYPE_FLOAT, 5, 28, offsetof(mavlink_trajectory_representation_waypoints_t, pos_y) }, \ - { "pos_z", NULL, MAVLINK_TYPE_FLOAT, 5, 48, offsetof(mavlink_trajectory_representation_waypoints_t, pos_z) }, \ - { "vel_x", NULL, MAVLINK_TYPE_FLOAT, 5, 68, offsetof(mavlink_trajectory_representation_waypoints_t, vel_x) }, \ - { "vel_y", NULL, MAVLINK_TYPE_FLOAT, 5, 88, offsetof(mavlink_trajectory_representation_waypoints_t, vel_y) }, \ - { "vel_z", NULL, MAVLINK_TYPE_FLOAT, 5, 108, offsetof(mavlink_trajectory_representation_waypoints_t, vel_z) }, \ - { "acc_x", NULL, MAVLINK_TYPE_FLOAT, 5, 128, offsetof(mavlink_trajectory_representation_waypoints_t, acc_x) }, \ - { "acc_y", NULL, MAVLINK_TYPE_FLOAT, 5, 148, offsetof(mavlink_trajectory_representation_waypoints_t, acc_y) }, \ - { "acc_z", NULL, MAVLINK_TYPE_FLOAT, 5, 168, offsetof(mavlink_trajectory_representation_waypoints_t, acc_z) }, \ - { "pos_yaw", NULL, MAVLINK_TYPE_FLOAT, 5, 188, offsetof(mavlink_trajectory_representation_waypoints_t, pos_yaw) }, \ - { "vel_yaw", NULL, MAVLINK_TYPE_FLOAT, 5, 208, offsetof(mavlink_trajectory_representation_waypoints_t, vel_yaw) }, \ - { "command", NULL, MAVLINK_TYPE_UINT16_T, 5, 228, offsetof(mavlink_trajectory_representation_waypoints_t, command) }, \ - } \ -} -#endif - -/** - * @brief Pack a trajectory_representation_waypoints message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @param valid_points Number of valid points (up-to 5 waypoints are possible) - * @param pos_x [m] X-coordinate of waypoint, set to NaN if not being used - * @param pos_y [m] Y-coordinate of waypoint, set to NaN if not being used - * @param pos_z [m] Z-coordinate of waypoint, set to NaN if not being used - * @param vel_x [m/s] X-velocity of waypoint, set to NaN if not being used - * @param vel_y [m/s] Y-velocity of waypoint, set to NaN if not being used - * @param vel_z [m/s] Z-velocity of waypoint, set to NaN if not being used - * @param acc_x [m/s/s] X-acceleration of waypoint, set to NaN if not being used - * @param acc_y [m/s/s] Y-acceleration of waypoint, set to NaN if not being used - * @param acc_z [m/s/s] Z-acceleration of waypoint, set to NaN if not being used - * @param pos_yaw [rad] Yaw angle, set to NaN if not being used - * @param vel_yaw [rad/s] Yaw rate, set to NaN if not being used - * @param command MAV_CMD command id of waypoint, set to UINT16_MAX if not being used. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_trajectory_representation_waypoints_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint64_t time_usec, uint8_t valid_points, const float *pos_x, const float *pos_y, const float *pos_z, const float *vel_x, const float *vel_y, const float *vel_z, const float *acc_x, const float *acc_y, const float *acc_z, const float *pos_yaw, const float *vel_yaw, const uint16_t *command) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_TRAJECTORY_REPRESENTATION_WAYPOINTS_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint8_t(buf, 238, valid_points); - _mav_put_float_array(buf, 8, pos_x, 5); - _mav_put_float_array(buf, 28, pos_y, 5); - _mav_put_float_array(buf, 48, pos_z, 5); - _mav_put_float_array(buf, 68, vel_x, 5); - _mav_put_float_array(buf, 88, vel_y, 5); - _mav_put_float_array(buf, 108, vel_z, 5); - _mav_put_float_array(buf, 128, acc_x, 5); - _mav_put_float_array(buf, 148, acc_y, 5); - _mav_put_float_array(buf, 168, acc_z, 5); - _mav_put_float_array(buf, 188, pos_yaw, 5); - _mav_put_float_array(buf, 208, vel_yaw, 5); - _mav_put_uint16_t_array(buf, 228, command, 5); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_TRAJECTORY_REPRESENTATION_WAYPOINTS_LEN); -#else - mavlink_trajectory_representation_waypoints_t packet; - packet.time_usec = time_usec; - packet.valid_points = valid_points; - mav_array_memcpy(packet.pos_x, pos_x, sizeof(float)*5); - mav_array_memcpy(packet.pos_y, pos_y, sizeof(float)*5); - mav_array_memcpy(packet.pos_z, pos_z, sizeof(float)*5); - mav_array_memcpy(packet.vel_x, vel_x, sizeof(float)*5); - mav_array_memcpy(packet.vel_y, vel_y, sizeof(float)*5); - mav_array_memcpy(packet.vel_z, vel_z, sizeof(float)*5); - mav_array_memcpy(packet.acc_x, acc_x, sizeof(float)*5); - mav_array_memcpy(packet.acc_y, acc_y, sizeof(float)*5); - mav_array_memcpy(packet.acc_z, acc_z, sizeof(float)*5); - mav_array_memcpy(packet.pos_yaw, pos_yaw, sizeof(float)*5); - mav_array_memcpy(packet.vel_yaw, vel_yaw, sizeof(float)*5); - mav_array_memcpy(packet.command, command, sizeof(uint16_t)*5); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_TRAJECTORY_REPRESENTATION_WAYPOINTS_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_TRAJECTORY_REPRESENTATION_WAYPOINTS; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_TRAJECTORY_REPRESENTATION_WAYPOINTS_MIN_LEN, MAVLINK_MSG_ID_TRAJECTORY_REPRESENTATION_WAYPOINTS_LEN, MAVLINK_MSG_ID_TRAJECTORY_REPRESENTATION_WAYPOINTS_CRC); -} - -/** - * @brief Pack a trajectory_representation_waypoints message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @param valid_points Number of valid points (up-to 5 waypoints are possible) - * @param pos_x [m] X-coordinate of waypoint, set to NaN if not being used - * @param pos_y [m] Y-coordinate of waypoint, set to NaN if not being used - * @param pos_z [m] Z-coordinate of waypoint, set to NaN if not being used - * @param vel_x [m/s] X-velocity of waypoint, set to NaN if not being used - * @param vel_y [m/s] Y-velocity of waypoint, set to NaN if not being used - * @param vel_z [m/s] Z-velocity of waypoint, set to NaN if not being used - * @param acc_x [m/s/s] X-acceleration of waypoint, set to NaN if not being used - * @param acc_y [m/s/s] Y-acceleration of waypoint, set to NaN if not being used - * @param acc_z [m/s/s] Z-acceleration of waypoint, set to NaN if not being used - * @param pos_yaw [rad] Yaw angle, set to NaN if not being used - * @param vel_yaw [rad/s] Yaw rate, set to NaN if not being used - * @param command MAV_CMD command id of waypoint, set to UINT16_MAX if not being used. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_trajectory_representation_waypoints_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint64_t time_usec,uint8_t valid_points,const float *pos_x,const float *pos_y,const float *pos_z,const float *vel_x,const float *vel_y,const float *vel_z,const float *acc_x,const float *acc_y,const float *acc_z,const float *pos_yaw,const float *vel_yaw,const uint16_t *command) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_TRAJECTORY_REPRESENTATION_WAYPOINTS_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint8_t(buf, 238, valid_points); - _mav_put_float_array(buf, 8, pos_x, 5); - _mav_put_float_array(buf, 28, pos_y, 5); - _mav_put_float_array(buf, 48, pos_z, 5); - _mav_put_float_array(buf, 68, vel_x, 5); - _mav_put_float_array(buf, 88, vel_y, 5); - _mav_put_float_array(buf, 108, vel_z, 5); - _mav_put_float_array(buf, 128, acc_x, 5); - _mav_put_float_array(buf, 148, acc_y, 5); - _mav_put_float_array(buf, 168, acc_z, 5); - _mav_put_float_array(buf, 188, pos_yaw, 5); - _mav_put_float_array(buf, 208, vel_yaw, 5); - _mav_put_uint16_t_array(buf, 228, command, 5); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_TRAJECTORY_REPRESENTATION_WAYPOINTS_LEN); -#else - mavlink_trajectory_representation_waypoints_t packet; - packet.time_usec = time_usec; - packet.valid_points = valid_points; - mav_array_memcpy(packet.pos_x, pos_x, sizeof(float)*5); - mav_array_memcpy(packet.pos_y, pos_y, sizeof(float)*5); - mav_array_memcpy(packet.pos_z, pos_z, sizeof(float)*5); - mav_array_memcpy(packet.vel_x, vel_x, sizeof(float)*5); - mav_array_memcpy(packet.vel_y, vel_y, sizeof(float)*5); - mav_array_memcpy(packet.vel_z, vel_z, sizeof(float)*5); - mav_array_memcpy(packet.acc_x, acc_x, sizeof(float)*5); - mav_array_memcpy(packet.acc_y, acc_y, sizeof(float)*5); - mav_array_memcpy(packet.acc_z, acc_z, sizeof(float)*5); - mav_array_memcpy(packet.pos_yaw, pos_yaw, sizeof(float)*5); - mav_array_memcpy(packet.vel_yaw, vel_yaw, sizeof(float)*5); - mav_array_memcpy(packet.command, command, sizeof(uint16_t)*5); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_TRAJECTORY_REPRESENTATION_WAYPOINTS_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_TRAJECTORY_REPRESENTATION_WAYPOINTS; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_TRAJECTORY_REPRESENTATION_WAYPOINTS_MIN_LEN, MAVLINK_MSG_ID_TRAJECTORY_REPRESENTATION_WAYPOINTS_LEN, MAVLINK_MSG_ID_TRAJECTORY_REPRESENTATION_WAYPOINTS_CRC); -} - -/** - * @brief Encode a trajectory_representation_waypoints struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param trajectory_representation_waypoints C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_trajectory_representation_waypoints_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_trajectory_representation_waypoints_t* trajectory_representation_waypoints) -{ - return mavlink_msg_trajectory_representation_waypoints_pack(system_id, component_id, msg, trajectory_representation_waypoints->time_usec, trajectory_representation_waypoints->valid_points, trajectory_representation_waypoints->pos_x, trajectory_representation_waypoints->pos_y, trajectory_representation_waypoints->pos_z, trajectory_representation_waypoints->vel_x, trajectory_representation_waypoints->vel_y, trajectory_representation_waypoints->vel_z, trajectory_representation_waypoints->acc_x, trajectory_representation_waypoints->acc_y, trajectory_representation_waypoints->acc_z, trajectory_representation_waypoints->pos_yaw, trajectory_representation_waypoints->vel_yaw, trajectory_representation_waypoints->command); -} - -/** - * @brief Encode a trajectory_representation_waypoints struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param trajectory_representation_waypoints C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_trajectory_representation_waypoints_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_trajectory_representation_waypoints_t* trajectory_representation_waypoints) -{ - return mavlink_msg_trajectory_representation_waypoints_pack_chan(system_id, component_id, chan, msg, trajectory_representation_waypoints->time_usec, trajectory_representation_waypoints->valid_points, trajectory_representation_waypoints->pos_x, trajectory_representation_waypoints->pos_y, trajectory_representation_waypoints->pos_z, trajectory_representation_waypoints->vel_x, trajectory_representation_waypoints->vel_y, trajectory_representation_waypoints->vel_z, trajectory_representation_waypoints->acc_x, trajectory_representation_waypoints->acc_y, trajectory_representation_waypoints->acc_z, trajectory_representation_waypoints->pos_yaw, trajectory_representation_waypoints->vel_yaw, trajectory_representation_waypoints->command); -} - -/** - * @brief Send a trajectory_representation_waypoints message - * @param chan MAVLink channel to send the message - * - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @param valid_points Number of valid points (up-to 5 waypoints are possible) - * @param pos_x [m] X-coordinate of waypoint, set to NaN if not being used - * @param pos_y [m] Y-coordinate of waypoint, set to NaN if not being used - * @param pos_z [m] Z-coordinate of waypoint, set to NaN if not being used - * @param vel_x [m/s] X-velocity of waypoint, set to NaN if not being used - * @param vel_y [m/s] Y-velocity of waypoint, set to NaN if not being used - * @param vel_z [m/s] Z-velocity of waypoint, set to NaN if not being used - * @param acc_x [m/s/s] X-acceleration of waypoint, set to NaN if not being used - * @param acc_y [m/s/s] Y-acceleration of waypoint, set to NaN if not being used - * @param acc_z [m/s/s] Z-acceleration of waypoint, set to NaN if not being used - * @param pos_yaw [rad] Yaw angle, set to NaN if not being used - * @param vel_yaw [rad/s] Yaw rate, set to NaN if not being used - * @param command MAV_CMD command id of waypoint, set to UINT16_MAX if not being used. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_trajectory_representation_waypoints_send(mavlink_channel_t chan, uint64_t time_usec, uint8_t valid_points, const float *pos_x, const float *pos_y, const float *pos_z, const float *vel_x, const float *vel_y, const float *vel_z, const float *acc_x, const float *acc_y, const float *acc_z, const float *pos_yaw, const float *vel_yaw, const uint16_t *command) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_TRAJECTORY_REPRESENTATION_WAYPOINTS_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint8_t(buf, 238, valid_points); - _mav_put_float_array(buf, 8, pos_x, 5); - _mav_put_float_array(buf, 28, pos_y, 5); - _mav_put_float_array(buf, 48, pos_z, 5); - _mav_put_float_array(buf, 68, vel_x, 5); - _mav_put_float_array(buf, 88, vel_y, 5); - _mav_put_float_array(buf, 108, vel_z, 5); - _mav_put_float_array(buf, 128, acc_x, 5); - _mav_put_float_array(buf, 148, acc_y, 5); - _mav_put_float_array(buf, 168, acc_z, 5); - _mav_put_float_array(buf, 188, pos_yaw, 5); - _mav_put_float_array(buf, 208, vel_yaw, 5); - _mav_put_uint16_t_array(buf, 228, command, 5); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TRAJECTORY_REPRESENTATION_WAYPOINTS, buf, MAVLINK_MSG_ID_TRAJECTORY_REPRESENTATION_WAYPOINTS_MIN_LEN, MAVLINK_MSG_ID_TRAJECTORY_REPRESENTATION_WAYPOINTS_LEN, MAVLINK_MSG_ID_TRAJECTORY_REPRESENTATION_WAYPOINTS_CRC); -#else - mavlink_trajectory_representation_waypoints_t packet; - packet.time_usec = time_usec; - packet.valid_points = valid_points; - mav_array_memcpy(packet.pos_x, pos_x, sizeof(float)*5); - mav_array_memcpy(packet.pos_y, pos_y, sizeof(float)*5); - mav_array_memcpy(packet.pos_z, pos_z, sizeof(float)*5); - mav_array_memcpy(packet.vel_x, vel_x, sizeof(float)*5); - mav_array_memcpy(packet.vel_y, vel_y, sizeof(float)*5); - mav_array_memcpy(packet.vel_z, vel_z, sizeof(float)*5); - mav_array_memcpy(packet.acc_x, acc_x, sizeof(float)*5); - mav_array_memcpy(packet.acc_y, acc_y, sizeof(float)*5); - mav_array_memcpy(packet.acc_z, acc_z, sizeof(float)*5); - mav_array_memcpy(packet.pos_yaw, pos_yaw, sizeof(float)*5); - mav_array_memcpy(packet.vel_yaw, vel_yaw, sizeof(float)*5); - mav_array_memcpy(packet.command, command, sizeof(uint16_t)*5); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TRAJECTORY_REPRESENTATION_WAYPOINTS, (const char *)&packet, MAVLINK_MSG_ID_TRAJECTORY_REPRESENTATION_WAYPOINTS_MIN_LEN, MAVLINK_MSG_ID_TRAJECTORY_REPRESENTATION_WAYPOINTS_LEN, MAVLINK_MSG_ID_TRAJECTORY_REPRESENTATION_WAYPOINTS_CRC); -#endif -} - -/** - * @brief Send a trajectory_representation_waypoints message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_trajectory_representation_waypoints_send_struct(mavlink_channel_t chan, const mavlink_trajectory_representation_waypoints_t* trajectory_representation_waypoints) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_trajectory_representation_waypoints_send(chan, trajectory_representation_waypoints->time_usec, trajectory_representation_waypoints->valid_points, trajectory_representation_waypoints->pos_x, trajectory_representation_waypoints->pos_y, trajectory_representation_waypoints->pos_z, trajectory_representation_waypoints->vel_x, trajectory_representation_waypoints->vel_y, trajectory_representation_waypoints->vel_z, trajectory_representation_waypoints->acc_x, trajectory_representation_waypoints->acc_y, trajectory_representation_waypoints->acc_z, trajectory_representation_waypoints->pos_yaw, trajectory_representation_waypoints->vel_yaw, trajectory_representation_waypoints->command); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TRAJECTORY_REPRESENTATION_WAYPOINTS, (const char *)trajectory_representation_waypoints, MAVLINK_MSG_ID_TRAJECTORY_REPRESENTATION_WAYPOINTS_MIN_LEN, MAVLINK_MSG_ID_TRAJECTORY_REPRESENTATION_WAYPOINTS_LEN, MAVLINK_MSG_ID_TRAJECTORY_REPRESENTATION_WAYPOINTS_CRC); -#endif -} - -#if MAVLINK_MSG_ID_TRAJECTORY_REPRESENTATION_WAYPOINTS_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_trajectory_representation_waypoints_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, uint8_t valid_points, const float *pos_x, const float *pos_y, const float *pos_z, const float *vel_x, const float *vel_y, const float *vel_z, const float *acc_x, const float *acc_y, const float *acc_z, const float *pos_yaw, const float *vel_yaw, const uint16_t *command) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint8_t(buf, 238, valid_points); - _mav_put_float_array(buf, 8, pos_x, 5); - _mav_put_float_array(buf, 28, pos_y, 5); - _mav_put_float_array(buf, 48, pos_z, 5); - _mav_put_float_array(buf, 68, vel_x, 5); - _mav_put_float_array(buf, 88, vel_y, 5); - _mav_put_float_array(buf, 108, vel_z, 5); - _mav_put_float_array(buf, 128, acc_x, 5); - _mav_put_float_array(buf, 148, acc_y, 5); - _mav_put_float_array(buf, 168, acc_z, 5); - _mav_put_float_array(buf, 188, pos_yaw, 5); - _mav_put_float_array(buf, 208, vel_yaw, 5); - _mav_put_uint16_t_array(buf, 228, command, 5); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TRAJECTORY_REPRESENTATION_WAYPOINTS, buf, MAVLINK_MSG_ID_TRAJECTORY_REPRESENTATION_WAYPOINTS_MIN_LEN, MAVLINK_MSG_ID_TRAJECTORY_REPRESENTATION_WAYPOINTS_LEN, MAVLINK_MSG_ID_TRAJECTORY_REPRESENTATION_WAYPOINTS_CRC); -#else - mavlink_trajectory_representation_waypoints_t *packet = (mavlink_trajectory_representation_waypoints_t *)msgbuf; - packet->time_usec = time_usec; - packet->valid_points = valid_points; - mav_array_memcpy(packet->pos_x, pos_x, sizeof(float)*5); - mav_array_memcpy(packet->pos_y, pos_y, sizeof(float)*5); - mav_array_memcpy(packet->pos_z, pos_z, sizeof(float)*5); - mav_array_memcpy(packet->vel_x, vel_x, sizeof(float)*5); - mav_array_memcpy(packet->vel_y, vel_y, sizeof(float)*5); - mav_array_memcpy(packet->vel_z, vel_z, sizeof(float)*5); - mav_array_memcpy(packet->acc_x, acc_x, sizeof(float)*5); - mav_array_memcpy(packet->acc_y, acc_y, sizeof(float)*5); - mav_array_memcpy(packet->acc_z, acc_z, sizeof(float)*5); - mav_array_memcpy(packet->pos_yaw, pos_yaw, sizeof(float)*5); - mav_array_memcpy(packet->vel_yaw, vel_yaw, sizeof(float)*5); - mav_array_memcpy(packet->command, command, sizeof(uint16_t)*5); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TRAJECTORY_REPRESENTATION_WAYPOINTS, (const char *)packet, MAVLINK_MSG_ID_TRAJECTORY_REPRESENTATION_WAYPOINTS_MIN_LEN, MAVLINK_MSG_ID_TRAJECTORY_REPRESENTATION_WAYPOINTS_LEN, MAVLINK_MSG_ID_TRAJECTORY_REPRESENTATION_WAYPOINTS_CRC); -#endif -} -#endif - -#endif - -// MESSAGE TRAJECTORY_REPRESENTATION_WAYPOINTS UNPACKING - - -/** - * @brief Get field time_usec from trajectory_representation_waypoints message - * - * @return [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - */ -static inline uint64_t mavlink_msg_trajectory_representation_waypoints_get_time_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field valid_points from trajectory_representation_waypoints message - * - * @return Number of valid points (up-to 5 waypoints are possible) - */ -static inline uint8_t mavlink_msg_trajectory_representation_waypoints_get_valid_points(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 238); -} - -/** - * @brief Get field pos_x from trajectory_representation_waypoints message - * - * @return [m] X-coordinate of waypoint, set to NaN if not being used - */ -static inline uint16_t mavlink_msg_trajectory_representation_waypoints_get_pos_x(const mavlink_message_t* msg, float *pos_x) -{ - return _MAV_RETURN_float_array(msg, pos_x, 5, 8); -} - -/** - * @brief Get field pos_y from trajectory_representation_waypoints message - * - * @return [m] Y-coordinate of waypoint, set to NaN if not being used - */ -static inline uint16_t mavlink_msg_trajectory_representation_waypoints_get_pos_y(const mavlink_message_t* msg, float *pos_y) -{ - return _MAV_RETURN_float_array(msg, pos_y, 5, 28); -} - -/** - * @brief Get field pos_z from trajectory_representation_waypoints message - * - * @return [m] Z-coordinate of waypoint, set to NaN if not being used - */ -static inline uint16_t mavlink_msg_trajectory_representation_waypoints_get_pos_z(const mavlink_message_t* msg, float *pos_z) -{ - return _MAV_RETURN_float_array(msg, pos_z, 5, 48); -} - -/** - * @brief Get field vel_x from trajectory_representation_waypoints message - * - * @return [m/s] X-velocity of waypoint, set to NaN if not being used - */ -static inline uint16_t mavlink_msg_trajectory_representation_waypoints_get_vel_x(const mavlink_message_t* msg, float *vel_x) -{ - return _MAV_RETURN_float_array(msg, vel_x, 5, 68); -} - -/** - * @brief Get field vel_y from trajectory_representation_waypoints message - * - * @return [m/s] Y-velocity of waypoint, set to NaN if not being used - */ -static inline uint16_t mavlink_msg_trajectory_representation_waypoints_get_vel_y(const mavlink_message_t* msg, float *vel_y) -{ - return _MAV_RETURN_float_array(msg, vel_y, 5, 88); -} - -/** - * @brief Get field vel_z from trajectory_representation_waypoints message - * - * @return [m/s] Z-velocity of waypoint, set to NaN if not being used - */ -static inline uint16_t mavlink_msg_trajectory_representation_waypoints_get_vel_z(const mavlink_message_t* msg, float *vel_z) -{ - return _MAV_RETURN_float_array(msg, vel_z, 5, 108); -} - -/** - * @brief Get field acc_x from trajectory_representation_waypoints message - * - * @return [m/s/s] X-acceleration of waypoint, set to NaN if not being used - */ -static inline uint16_t mavlink_msg_trajectory_representation_waypoints_get_acc_x(const mavlink_message_t* msg, float *acc_x) -{ - return _MAV_RETURN_float_array(msg, acc_x, 5, 128); -} - -/** - * @brief Get field acc_y from trajectory_representation_waypoints message - * - * @return [m/s/s] Y-acceleration of waypoint, set to NaN if not being used - */ -static inline uint16_t mavlink_msg_trajectory_representation_waypoints_get_acc_y(const mavlink_message_t* msg, float *acc_y) -{ - return _MAV_RETURN_float_array(msg, acc_y, 5, 148); -} - -/** - * @brief Get field acc_z from trajectory_representation_waypoints message - * - * @return [m/s/s] Z-acceleration of waypoint, set to NaN if not being used - */ -static inline uint16_t mavlink_msg_trajectory_representation_waypoints_get_acc_z(const mavlink_message_t* msg, float *acc_z) -{ - return _MAV_RETURN_float_array(msg, acc_z, 5, 168); -} - -/** - * @brief Get field pos_yaw from trajectory_representation_waypoints message - * - * @return [rad] Yaw angle, set to NaN if not being used - */ -static inline uint16_t mavlink_msg_trajectory_representation_waypoints_get_pos_yaw(const mavlink_message_t* msg, float *pos_yaw) -{ - return _MAV_RETURN_float_array(msg, pos_yaw, 5, 188); -} - -/** - * @brief Get field vel_yaw from trajectory_representation_waypoints message - * - * @return [rad/s] Yaw rate, set to NaN if not being used - */ -static inline uint16_t mavlink_msg_trajectory_representation_waypoints_get_vel_yaw(const mavlink_message_t* msg, float *vel_yaw) -{ - return _MAV_RETURN_float_array(msg, vel_yaw, 5, 208); -} - -/** - * @brief Get field command from trajectory_representation_waypoints message - * - * @return MAV_CMD command id of waypoint, set to UINT16_MAX if not being used. - */ -static inline uint16_t mavlink_msg_trajectory_representation_waypoints_get_command(const mavlink_message_t* msg, uint16_t *command) -{ - return _MAV_RETURN_uint16_t_array(msg, command, 5, 228); -} - -/** - * @brief Decode a trajectory_representation_waypoints message into a struct - * - * @param msg The message to decode - * @param trajectory_representation_waypoints C-struct to decode the message contents into - */ -static inline void mavlink_msg_trajectory_representation_waypoints_decode(const mavlink_message_t* msg, mavlink_trajectory_representation_waypoints_t* trajectory_representation_waypoints) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - trajectory_representation_waypoints->time_usec = mavlink_msg_trajectory_representation_waypoints_get_time_usec(msg); - mavlink_msg_trajectory_representation_waypoints_get_pos_x(msg, trajectory_representation_waypoints->pos_x); - mavlink_msg_trajectory_representation_waypoints_get_pos_y(msg, trajectory_representation_waypoints->pos_y); - mavlink_msg_trajectory_representation_waypoints_get_pos_z(msg, trajectory_representation_waypoints->pos_z); - mavlink_msg_trajectory_representation_waypoints_get_vel_x(msg, trajectory_representation_waypoints->vel_x); - mavlink_msg_trajectory_representation_waypoints_get_vel_y(msg, trajectory_representation_waypoints->vel_y); - mavlink_msg_trajectory_representation_waypoints_get_vel_z(msg, trajectory_representation_waypoints->vel_z); - mavlink_msg_trajectory_representation_waypoints_get_acc_x(msg, trajectory_representation_waypoints->acc_x); - mavlink_msg_trajectory_representation_waypoints_get_acc_y(msg, trajectory_representation_waypoints->acc_y); - mavlink_msg_trajectory_representation_waypoints_get_acc_z(msg, trajectory_representation_waypoints->acc_z); - mavlink_msg_trajectory_representation_waypoints_get_pos_yaw(msg, trajectory_representation_waypoints->pos_yaw); - mavlink_msg_trajectory_representation_waypoints_get_vel_yaw(msg, trajectory_representation_waypoints->vel_yaw); - mavlink_msg_trajectory_representation_waypoints_get_command(msg, trajectory_representation_waypoints->command); - trajectory_representation_waypoints->valid_points = mavlink_msg_trajectory_representation_waypoints_get_valid_points(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_TRAJECTORY_REPRESENTATION_WAYPOINTS_LEN? msg->len : MAVLINK_MSG_ID_TRAJECTORY_REPRESENTATION_WAYPOINTS_LEN; - memset(trajectory_representation_waypoints, 0, MAVLINK_MSG_ID_TRAJECTORY_REPRESENTATION_WAYPOINTS_LEN); - memcpy(trajectory_representation_waypoints, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_tunnel.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_tunnel.h deleted file mode 100644 index 1541e134..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_tunnel.h +++ /dev/null @@ -1,305 +0,0 @@ -#pragma once -// MESSAGE TUNNEL PACKING - -#define MAVLINK_MSG_ID_TUNNEL 385 - - -typedef struct __mavlink_tunnel_t { - uint16_t payload_type; /*< A code that identifies the content of the payload (0 for unknown, which is the default). If this code is less than 32768, it is a 'registered' payload type and the corresponding code should be added to the MAV_TUNNEL_PAYLOAD_TYPE enum. Software creators can register blocks of types as needed. Codes greater than 32767 are considered local experiments and should not be checked in to any widely distributed codebase.*/ - uint8_t target_system; /*< System ID (can be 0 for broadcast, but this is discouraged)*/ - uint8_t target_component; /*< Component ID (can be 0 for broadcast, but this is discouraged)*/ - uint8_t payload_length; /*< Length of the data transported in payload*/ - uint8_t payload[128]; /*< Variable length payload. The payload length is defined by payload_length. The entire content of this block is opaque unless you understand the encoding specified by payload_type.*/ -} mavlink_tunnel_t; - -#define MAVLINK_MSG_ID_TUNNEL_LEN 133 -#define MAVLINK_MSG_ID_TUNNEL_MIN_LEN 133 -#define MAVLINK_MSG_ID_385_LEN 133 -#define MAVLINK_MSG_ID_385_MIN_LEN 133 - -#define MAVLINK_MSG_ID_TUNNEL_CRC 147 -#define MAVLINK_MSG_ID_385_CRC 147 - -#define MAVLINK_MSG_TUNNEL_FIELD_PAYLOAD_LEN 128 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_TUNNEL { \ - 385, \ - "TUNNEL", \ - 5, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_tunnel_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_tunnel_t, target_component) }, \ - { "payload_type", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_tunnel_t, payload_type) }, \ - { "payload_length", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_tunnel_t, payload_length) }, \ - { "payload", NULL, MAVLINK_TYPE_UINT8_T, 128, 5, offsetof(mavlink_tunnel_t, payload) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_TUNNEL { \ - "TUNNEL", \ - 5, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_tunnel_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_tunnel_t, target_component) }, \ - { "payload_type", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_tunnel_t, payload_type) }, \ - { "payload_length", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_tunnel_t, payload_length) }, \ - { "payload", NULL, MAVLINK_TYPE_UINT8_T, 128, 5, offsetof(mavlink_tunnel_t, payload) }, \ - } \ -} -#endif - -/** - * @brief Pack a tunnel message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID (can be 0 for broadcast, but this is discouraged) - * @param target_component Component ID (can be 0 for broadcast, but this is discouraged) - * @param payload_type A code that identifies the content of the payload (0 for unknown, which is the default). If this code is less than 32768, it is a 'registered' payload type and the corresponding code should be added to the MAV_TUNNEL_PAYLOAD_TYPE enum. Software creators can register blocks of types as needed. Codes greater than 32767 are considered local experiments and should not be checked in to any widely distributed codebase. - * @param payload_length Length of the data transported in payload - * @param payload Variable length payload. The payload length is defined by payload_length. The entire content of this block is opaque unless you understand the encoding specified by payload_type. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_tunnel_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component, uint16_t payload_type, uint8_t payload_length, const uint8_t *payload) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_TUNNEL_LEN]; - _mav_put_uint16_t(buf, 0, payload_type); - _mav_put_uint8_t(buf, 2, target_system); - _mav_put_uint8_t(buf, 3, target_component); - _mav_put_uint8_t(buf, 4, payload_length); - _mav_put_uint8_t_array(buf, 5, payload, 128); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_TUNNEL_LEN); -#else - mavlink_tunnel_t packet; - packet.payload_type = payload_type; - packet.target_system = target_system; - packet.target_component = target_component; - packet.payload_length = payload_length; - mav_array_memcpy(packet.payload, payload, sizeof(uint8_t)*128); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_TUNNEL_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_TUNNEL; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_TUNNEL_MIN_LEN, MAVLINK_MSG_ID_TUNNEL_LEN, MAVLINK_MSG_ID_TUNNEL_CRC); -} - -/** - * @brief Pack a tunnel message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID (can be 0 for broadcast, but this is discouraged) - * @param target_component Component ID (can be 0 for broadcast, but this is discouraged) - * @param payload_type A code that identifies the content of the payload (0 for unknown, which is the default). If this code is less than 32768, it is a 'registered' payload type and the corresponding code should be added to the MAV_TUNNEL_PAYLOAD_TYPE enum. Software creators can register blocks of types as needed. Codes greater than 32767 are considered local experiments and should not be checked in to any widely distributed codebase. - * @param payload_length Length of the data transported in payload - * @param payload Variable length payload. The payload length is defined by payload_length. The entire content of this block is opaque unless you understand the encoding specified by payload_type. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_tunnel_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component,uint16_t payload_type,uint8_t payload_length,const uint8_t *payload) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_TUNNEL_LEN]; - _mav_put_uint16_t(buf, 0, payload_type); - _mav_put_uint8_t(buf, 2, target_system); - _mav_put_uint8_t(buf, 3, target_component); - _mav_put_uint8_t(buf, 4, payload_length); - _mav_put_uint8_t_array(buf, 5, payload, 128); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_TUNNEL_LEN); -#else - mavlink_tunnel_t packet; - packet.payload_type = payload_type; - packet.target_system = target_system; - packet.target_component = target_component; - packet.payload_length = payload_length; - mav_array_memcpy(packet.payload, payload, sizeof(uint8_t)*128); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_TUNNEL_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_TUNNEL; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_TUNNEL_MIN_LEN, MAVLINK_MSG_ID_TUNNEL_LEN, MAVLINK_MSG_ID_TUNNEL_CRC); -} - -/** - * @brief Encode a tunnel struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param tunnel C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_tunnel_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_tunnel_t* tunnel) -{ - return mavlink_msg_tunnel_pack(system_id, component_id, msg, tunnel->target_system, tunnel->target_component, tunnel->payload_type, tunnel->payload_length, tunnel->payload); -} - -/** - * @brief Encode a tunnel struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param tunnel C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_tunnel_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_tunnel_t* tunnel) -{ - return mavlink_msg_tunnel_pack_chan(system_id, component_id, chan, msg, tunnel->target_system, tunnel->target_component, tunnel->payload_type, tunnel->payload_length, tunnel->payload); -} - -/** - * @brief Send a tunnel message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID (can be 0 for broadcast, but this is discouraged) - * @param target_component Component ID (can be 0 for broadcast, but this is discouraged) - * @param payload_type A code that identifies the content of the payload (0 for unknown, which is the default). If this code is less than 32768, it is a 'registered' payload type and the corresponding code should be added to the MAV_TUNNEL_PAYLOAD_TYPE enum. Software creators can register blocks of types as needed. Codes greater than 32767 are considered local experiments and should not be checked in to any widely distributed codebase. - * @param payload_length Length of the data transported in payload - * @param payload Variable length payload. The payload length is defined by payload_length. The entire content of this block is opaque unless you understand the encoding specified by payload_type. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_tunnel_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t payload_type, uint8_t payload_length, const uint8_t *payload) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_TUNNEL_LEN]; - _mav_put_uint16_t(buf, 0, payload_type); - _mav_put_uint8_t(buf, 2, target_system); - _mav_put_uint8_t(buf, 3, target_component); - _mav_put_uint8_t(buf, 4, payload_length); - _mav_put_uint8_t_array(buf, 5, payload, 128); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TUNNEL, buf, MAVLINK_MSG_ID_TUNNEL_MIN_LEN, MAVLINK_MSG_ID_TUNNEL_LEN, MAVLINK_MSG_ID_TUNNEL_CRC); -#else - mavlink_tunnel_t packet; - packet.payload_type = payload_type; - packet.target_system = target_system; - packet.target_component = target_component; - packet.payload_length = payload_length; - mav_array_memcpy(packet.payload, payload, sizeof(uint8_t)*128); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TUNNEL, (const char *)&packet, MAVLINK_MSG_ID_TUNNEL_MIN_LEN, MAVLINK_MSG_ID_TUNNEL_LEN, MAVLINK_MSG_ID_TUNNEL_CRC); -#endif -} - -/** - * @brief Send a tunnel message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_tunnel_send_struct(mavlink_channel_t chan, const mavlink_tunnel_t* tunnel) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_tunnel_send(chan, tunnel->target_system, tunnel->target_component, tunnel->payload_type, tunnel->payload_length, tunnel->payload); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TUNNEL, (const char *)tunnel, MAVLINK_MSG_ID_TUNNEL_MIN_LEN, MAVLINK_MSG_ID_TUNNEL_LEN, MAVLINK_MSG_ID_TUNNEL_CRC); -#endif -} - -#if MAVLINK_MSG_ID_TUNNEL_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_tunnel_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t payload_type, uint8_t payload_length, const uint8_t *payload) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint16_t(buf, 0, payload_type); - _mav_put_uint8_t(buf, 2, target_system); - _mav_put_uint8_t(buf, 3, target_component); - _mav_put_uint8_t(buf, 4, payload_length); - _mav_put_uint8_t_array(buf, 5, payload, 128); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TUNNEL, buf, MAVLINK_MSG_ID_TUNNEL_MIN_LEN, MAVLINK_MSG_ID_TUNNEL_LEN, MAVLINK_MSG_ID_TUNNEL_CRC); -#else - mavlink_tunnel_t *packet = (mavlink_tunnel_t *)msgbuf; - packet->payload_type = payload_type; - packet->target_system = target_system; - packet->target_component = target_component; - packet->payload_length = payload_length; - mav_array_memcpy(packet->payload, payload, sizeof(uint8_t)*128); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TUNNEL, (const char *)packet, MAVLINK_MSG_ID_TUNNEL_MIN_LEN, MAVLINK_MSG_ID_TUNNEL_LEN, MAVLINK_MSG_ID_TUNNEL_CRC); -#endif -} -#endif - -#endif - -// MESSAGE TUNNEL UNPACKING - - -/** - * @brief Get field target_system from tunnel message - * - * @return System ID (can be 0 for broadcast, but this is discouraged) - */ -static inline uint8_t mavlink_msg_tunnel_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 2); -} - -/** - * @brief Get field target_component from tunnel message - * - * @return Component ID (can be 0 for broadcast, but this is discouraged) - */ -static inline uint8_t mavlink_msg_tunnel_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 3); -} - -/** - * @brief Get field payload_type from tunnel message - * - * @return A code that identifies the content of the payload (0 for unknown, which is the default). If this code is less than 32768, it is a 'registered' payload type and the corresponding code should be added to the MAV_TUNNEL_PAYLOAD_TYPE enum. Software creators can register blocks of types as needed. Codes greater than 32767 are considered local experiments and should not be checked in to any widely distributed codebase. - */ -static inline uint16_t mavlink_msg_tunnel_get_payload_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 0); -} - -/** - * @brief Get field payload_length from tunnel message - * - * @return Length of the data transported in payload - */ -static inline uint8_t mavlink_msg_tunnel_get_payload_length(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 4); -} - -/** - * @brief Get field payload from tunnel message - * - * @return Variable length payload. The payload length is defined by payload_length. The entire content of this block is opaque unless you understand the encoding specified by payload_type. - */ -static inline uint16_t mavlink_msg_tunnel_get_payload(const mavlink_message_t* msg, uint8_t *payload) -{ - return _MAV_RETURN_uint8_t_array(msg, payload, 128, 5); -} - -/** - * @brief Decode a tunnel message into a struct - * - * @param msg The message to decode - * @param tunnel C-struct to decode the message contents into - */ -static inline void mavlink_msg_tunnel_decode(const mavlink_message_t* msg, mavlink_tunnel_t* tunnel) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - tunnel->payload_type = mavlink_msg_tunnel_get_payload_type(msg); - tunnel->target_system = mavlink_msg_tunnel_get_target_system(msg); - tunnel->target_component = mavlink_msg_tunnel_get_target_component(msg); - tunnel->payload_length = mavlink_msg_tunnel_get_payload_length(msg); - mavlink_msg_tunnel_get_payload(msg, tunnel->payload); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_TUNNEL_LEN? msg->len : MAVLINK_MSG_ID_TUNNEL_LEN; - memset(tunnel, 0, MAVLINK_MSG_ID_TUNNEL_LEN); - memcpy(tunnel, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_uavcan_node_info.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_uavcan_node_info.h deleted file mode 100644 index 83a4be5a..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_uavcan_node_info.h +++ /dev/null @@ -1,406 +0,0 @@ -#pragma once -// MESSAGE UAVCAN_NODE_INFO PACKING - -#define MAVLINK_MSG_ID_UAVCAN_NODE_INFO 311 - - -typedef struct __mavlink_uavcan_node_info_t { - uint64_t time_usec; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/ - uint32_t uptime_sec; /*< [s] Time since the start-up of the node.*/ - uint32_t sw_vcs_commit; /*< Version control system (VCS) revision identifier (e.g. git short commit hash). 0 if unknown.*/ - char name[80]; /*< Node name string. For example, "sapog.px4.io".*/ - uint8_t hw_version_major; /*< Hardware major version number.*/ - uint8_t hw_version_minor; /*< Hardware minor version number.*/ - uint8_t hw_unique_id[16]; /*< Hardware unique 128-bit ID.*/ - uint8_t sw_version_major; /*< Software major version number.*/ - uint8_t sw_version_minor; /*< Software minor version number.*/ -} mavlink_uavcan_node_info_t; - -#define MAVLINK_MSG_ID_UAVCAN_NODE_INFO_LEN 116 -#define MAVLINK_MSG_ID_UAVCAN_NODE_INFO_MIN_LEN 116 -#define MAVLINK_MSG_ID_311_LEN 116 -#define MAVLINK_MSG_ID_311_MIN_LEN 116 - -#define MAVLINK_MSG_ID_UAVCAN_NODE_INFO_CRC 95 -#define MAVLINK_MSG_ID_311_CRC 95 - -#define MAVLINK_MSG_UAVCAN_NODE_INFO_FIELD_NAME_LEN 80 -#define MAVLINK_MSG_UAVCAN_NODE_INFO_FIELD_HW_UNIQUE_ID_LEN 16 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_UAVCAN_NODE_INFO { \ - 311, \ - "UAVCAN_NODE_INFO", \ - 9, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_uavcan_node_info_t, time_usec) }, \ - { "uptime_sec", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_uavcan_node_info_t, uptime_sec) }, \ - { "name", NULL, MAVLINK_TYPE_CHAR, 80, 16, offsetof(mavlink_uavcan_node_info_t, name) }, \ - { "hw_version_major", NULL, MAVLINK_TYPE_UINT8_T, 0, 96, offsetof(mavlink_uavcan_node_info_t, hw_version_major) }, \ - { "hw_version_minor", NULL, MAVLINK_TYPE_UINT8_T, 0, 97, offsetof(mavlink_uavcan_node_info_t, hw_version_minor) }, \ - { "hw_unique_id", NULL, MAVLINK_TYPE_UINT8_T, 16, 98, offsetof(mavlink_uavcan_node_info_t, hw_unique_id) }, \ - { "sw_version_major", NULL, MAVLINK_TYPE_UINT8_T, 0, 114, offsetof(mavlink_uavcan_node_info_t, sw_version_major) }, \ - { "sw_version_minor", NULL, MAVLINK_TYPE_UINT8_T, 0, 115, offsetof(mavlink_uavcan_node_info_t, sw_version_minor) }, \ - { "sw_vcs_commit", NULL, MAVLINK_TYPE_UINT32_T, 0, 12, offsetof(mavlink_uavcan_node_info_t, sw_vcs_commit) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_UAVCAN_NODE_INFO { \ - "UAVCAN_NODE_INFO", \ - 9, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_uavcan_node_info_t, time_usec) }, \ - { "uptime_sec", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_uavcan_node_info_t, uptime_sec) }, \ - { "name", NULL, MAVLINK_TYPE_CHAR, 80, 16, offsetof(mavlink_uavcan_node_info_t, name) }, \ - { "hw_version_major", NULL, MAVLINK_TYPE_UINT8_T, 0, 96, offsetof(mavlink_uavcan_node_info_t, hw_version_major) }, \ - { "hw_version_minor", NULL, MAVLINK_TYPE_UINT8_T, 0, 97, offsetof(mavlink_uavcan_node_info_t, hw_version_minor) }, \ - { "hw_unique_id", NULL, MAVLINK_TYPE_UINT8_T, 16, 98, offsetof(mavlink_uavcan_node_info_t, hw_unique_id) }, \ - { "sw_version_major", NULL, MAVLINK_TYPE_UINT8_T, 0, 114, offsetof(mavlink_uavcan_node_info_t, sw_version_major) }, \ - { "sw_version_minor", NULL, MAVLINK_TYPE_UINT8_T, 0, 115, offsetof(mavlink_uavcan_node_info_t, sw_version_minor) }, \ - { "sw_vcs_commit", NULL, MAVLINK_TYPE_UINT32_T, 0, 12, offsetof(mavlink_uavcan_node_info_t, sw_vcs_commit) }, \ - } \ -} -#endif - -/** - * @brief Pack a uavcan_node_info message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @param uptime_sec [s] Time since the start-up of the node. - * @param name Node name string. For example, "sapog.px4.io". - * @param hw_version_major Hardware major version number. - * @param hw_version_minor Hardware minor version number. - * @param hw_unique_id Hardware unique 128-bit ID. - * @param sw_version_major Software major version number. - * @param sw_version_minor Software minor version number. - * @param sw_vcs_commit Version control system (VCS) revision identifier (e.g. git short commit hash). 0 if unknown. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_uavcan_node_info_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint64_t time_usec, uint32_t uptime_sec, const char *name, uint8_t hw_version_major, uint8_t hw_version_minor, const uint8_t *hw_unique_id, uint8_t sw_version_major, uint8_t sw_version_minor, uint32_t sw_vcs_commit) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_UAVCAN_NODE_INFO_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint32_t(buf, 8, uptime_sec); - _mav_put_uint32_t(buf, 12, sw_vcs_commit); - _mav_put_uint8_t(buf, 96, hw_version_major); - _mav_put_uint8_t(buf, 97, hw_version_minor); - _mav_put_uint8_t(buf, 114, sw_version_major); - _mav_put_uint8_t(buf, 115, sw_version_minor); - _mav_put_char_array(buf, 16, name, 80); - _mav_put_uint8_t_array(buf, 98, hw_unique_id, 16); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_UAVCAN_NODE_INFO_LEN); -#else - mavlink_uavcan_node_info_t packet; - packet.time_usec = time_usec; - packet.uptime_sec = uptime_sec; - packet.sw_vcs_commit = sw_vcs_commit; - packet.hw_version_major = hw_version_major; - packet.hw_version_minor = hw_version_minor; - packet.sw_version_major = sw_version_major; - packet.sw_version_minor = sw_version_minor; - mav_array_memcpy(packet.name, name, sizeof(char)*80); - mav_array_memcpy(packet.hw_unique_id, hw_unique_id, sizeof(uint8_t)*16); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_UAVCAN_NODE_INFO_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_UAVCAN_NODE_INFO; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_UAVCAN_NODE_INFO_MIN_LEN, MAVLINK_MSG_ID_UAVCAN_NODE_INFO_LEN, MAVLINK_MSG_ID_UAVCAN_NODE_INFO_CRC); -} - -/** - * @brief Pack a uavcan_node_info message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @param uptime_sec [s] Time since the start-up of the node. - * @param name Node name string. For example, "sapog.px4.io". - * @param hw_version_major Hardware major version number. - * @param hw_version_minor Hardware minor version number. - * @param hw_unique_id Hardware unique 128-bit ID. - * @param sw_version_major Software major version number. - * @param sw_version_minor Software minor version number. - * @param sw_vcs_commit Version control system (VCS) revision identifier (e.g. git short commit hash). 0 if unknown. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_uavcan_node_info_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint64_t time_usec,uint32_t uptime_sec,const char *name,uint8_t hw_version_major,uint8_t hw_version_minor,const uint8_t *hw_unique_id,uint8_t sw_version_major,uint8_t sw_version_minor,uint32_t sw_vcs_commit) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_UAVCAN_NODE_INFO_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint32_t(buf, 8, uptime_sec); - _mav_put_uint32_t(buf, 12, sw_vcs_commit); - _mav_put_uint8_t(buf, 96, hw_version_major); - _mav_put_uint8_t(buf, 97, hw_version_minor); - _mav_put_uint8_t(buf, 114, sw_version_major); - _mav_put_uint8_t(buf, 115, sw_version_minor); - _mav_put_char_array(buf, 16, name, 80); - _mav_put_uint8_t_array(buf, 98, hw_unique_id, 16); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_UAVCAN_NODE_INFO_LEN); -#else - mavlink_uavcan_node_info_t packet; - packet.time_usec = time_usec; - packet.uptime_sec = uptime_sec; - packet.sw_vcs_commit = sw_vcs_commit; - packet.hw_version_major = hw_version_major; - packet.hw_version_minor = hw_version_minor; - packet.sw_version_major = sw_version_major; - packet.sw_version_minor = sw_version_minor; - mav_array_memcpy(packet.name, name, sizeof(char)*80); - mav_array_memcpy(packet.hw_unique_id, hw_unique_id, sizeof(uint8_t)*16); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_UAVCAN_NODE_INFO_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_UAVCAN_NODE_INFO; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_UAVCAN_NODE_INFO_MIN_LEN, MAVLINK_MSG_ID_UAVCAN_NODE_INFO_LEN, MAVLINK_MSG_ID_UAVCAN_NODE_INFO_CRC); -} - -/** - * @brief Encode a uavcan_node_info struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param uavcan_node_info C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_uavcan_node_info_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_uavcan_node_info_t* uavcan_node_info) -{ - return mavlink_msg_uavcan_node_info_pack(system_id, component_id, msg, uavcan_node_info->time_usec, uavcan_node_info->uptime_sec, uavcan_node_info->name, uavcan_node_info->hw_version_major, uavcan_node_info->hw_version_minor, uavcan_node_info->hw_unique_id, uavcan_node_info->sw_version_major, uavcan_node_info->sw_version_minor, uavcan_node_info->sw_vcs_commit); -} - -/** - * @brief Encode a uavcan_node_info struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param uavcan_node_info C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_uavcan_node_info_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_uavcan_node_info_t* uavcan_node_info) -{ - return mavlink_msg_uavcan_node_info_pack_chan(system_id, component_id, chan, msg, uavcan_node_info->time_usec, uavcan_node_info->uptime_sec, uavcan_node_info->name, uavcan_node_info->hw_version_major, uavcan_node_info->hw_version_minor, uavcan_node_info->hw_unique_id, uavcan_node_info->sw_version_major, uavcan_node_info->sw_version_minor, uavcan_node_info->sw_vcs_commit); -} - -/** - * @brief Send a uavcan_node_info message - * @param chan MAVLink channel to send the message - * - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @param uptime_sec [s] Time since the start-up of the node. - * @param name Node name string. For example, "sapog.px4.io". - * @param hw_version_major Hardware major version number. - * @param hw_version_minor Hardware minor version number. - * @param hw_unique_id Hardware unique 128-bit ID. - * @param sw_version_major Software major version number. - * @param sw_version_minor Software minor version number. - * @param sw_vcs_commit Version control system (VCS) revision identifier (e.g. git short commit hash). 0 if unknown. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_uavcan_node_info_send(mavlink_channel_t chan, uint64_t time_usec, uint32_t uptime_sec, const char *name, uint8_t hw_version_major, uint8_t hw_version_minor, const uint8_t *hw_unique_id, uint8_t sw_version_major, uint8_t sw_version_minor, uint32_t sw_vcs_commit) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_UAVCAN_NODE_INFO_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint32_t(buf, 8, uptime_sec); - _mav_put_uint32_t(buf, 12, sw_vcs_commit); - _mav_put_uint8_t(buf, 96, hw_version_major); - _mav_put_uint8_t(buf, 97, hw_version_minor); - _mav_put_uint8_t(buf, 114, sw_version_major); - _mav_put_uint8_t(buf, 115, sw_version_minor); - _mav_put_char_array(buf, 16, name, 80); - _mav_put_uint8_t_array(buf, 98, hw_unique_id, 16); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_UAVCAN_NODE_INFO, buf, MAVLINK_MSG_ID_UAVCAN_NODE_INFO_MIN_LEN, MAVLINK_MSG_ID_UAVCAN_NODE_INFO_LEN, MAVLINK_MSG_ID_UAVCAN_NODE_INFO_CRC); -#else - mavlink_uavcan_node_info_t packet; - packet.time_usec = time_usec; - packet.uptime_sec = uptime_sec; - packet.sw_vcs_commit = sw_vcs_commit; - packet.hw_version_major = hw_version_major; - packet.hw_version_minor = hw_version_minor; - packet.sw_version_major = sw_version_major; - packet.sw_version_minor = sw_version_minor; - mav_array_memcpy(packet.name, name, sizeof(char)*80); - mav_array_memcpy(packet.hw_unique_id, hw_unique_id, sizeof(uint8_t)*16); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_UAVCAN_NODE_INFO, (const char *)&packet, MAVLINK_MSG_ID_UAVCAN_NODE_INFO_MIN_LEN, MAVLINK_MSG_ID_UAVCAN_NODE_INFO_LEN, MAVLINK_MSG_ID_UAVCAN_NODE_INFO_CRC); -#endif -} - -/** - * @brief Send a uavcan_node_info message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_uavcan_node_info_send_struct(mavlink_channel_t chan, const mavlink_uavcan_node_info_t* uavcan_node_info) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_uavcan_node_info_send(chan, uavcan_node_info->time_usec, uavcan_node_info->uptime_sec, uavcan_node_info->name, uavcan_node_info->hw_version_major, uavcan_node_info->hw_version_minor, uavcan_node_info->hw_unique_id, uavcan_node_info->sw_version_major, uavcan_node_info->sw_version_minor, uavcan_node_info->sw_vcs_commit); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_UAVCAN_NODE_INFO, (const char *)uavcan_node_info, MAVLINK_MSG_ID_UAVCAN_NODE_INFO_MIN_LEN, MAVLINK_MSG_ID_UAVCAN_NODE_INFO_LEN, MAVLINK_MSG_ID_UAVCAN_NODE_INFO_CRC); -#endif -} - -#if MAVLINK_MSG_ID_UAVCAN_NODE_INFO_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_uavcan_node_info_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, uint32_t uptime_sec, const char *name, uint8_t hw_version_major, uint8_t hw_version_minor, const uint8_t *hw_unique_id, uint8_t sw_version_major, uint8_t sw_version_minor, uint32_t sw_vcs_commit) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint32_t(buf, 8, uptime_sec); - _mav_put_uint32_t(buf, 12, sw_vcs_commit); - _mav_put_uint8_t(buf, 96, hw_version_major); - _mav_put_uint8_t(buf, 97, hw_version_minor); - _mav_put_uint8_t(buf, 114, sw_version_major); - _mav_put_uint8_t(buf, 115, sw_version_minor); - _mav_put_char_array(buf, 16, name, 80); - _mav_put_uint8_t_array(buf, 98, hw_unique_id, 16); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_UAVCAN_NODE_INFO, buf, MAVLINK_MSG_ID_UAVCAN_NODE_INFO_MIN_LEN, MAVLINK_MSG_ID_UAVCAN_NODE_INFO_LEN, MAVLINK_MSG_ID_UAVCAN_NODE_INFO_CRC); -#else - mavlink_uavcan_node_info_t *packet = (mavlink_uavcan_node_info_t *)msgbuf; - packet->time_usec = time_usec; - packet->uptime_sec = uptime_sec; - packet->sw_vcs_commit = sw_vcs_commit; - packet->hw_version_major = hw_version_major; - packet->hw_version_minor = hw_version_minor; - packet->sw_version_major = sw_version_major; - packet->sw_version_minor = sw_version_minor; - mav_array_memcpy(packet->name, name, sizeof(char)*80); - mav_array_memcpy(packet->hw_unique_id, hw_unique_id, sizeof(uint8_t)*16); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_UAVCAN_NODE_INFO, (const char *)packet, MAVLINK_MSG_ID_UAVCAN_NODE_INFO_MIN_LEN, MAVLINK_MSG_ID_UAVCAN_NODE_INFO_LEN, MAVLINK_MSG_ID_UAVCAN_NODE_INFO_CRC); -#endif -} -#endif - -#endif - -// MESSAGE UAVCAN_NODE_INFO UNPACKING - - -/** - * @brief Get field time_usec from uavcan_node_info message - * - * @return [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - */ -static inline uint64_t mavlink_msg_uavcan_node_info_get_time_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field uptime_sec from uavcan_node_info message - * - * @return [s] Time since the start-up of the node. - */ -static inline uint32_t mavlink_msg_uavcan_node_info_get_uptime_sec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 8); -} - -/** - * @brief Get field name from uavcan_node_info message - * - * @return Node name string. For example, "sapog.px4.io". - */ -static inline uint16_t mavlink_msg_uavcan_node_info_get_name(const mavlink_message_t* msg, char *name) -{ - return _MAV_RETURN_char_array(msg, name, 80, 16); -} - -/** - * @brief Get field hw_version_major from uavcan_node_info message - * - * @return Hardware major version number. - */ -static inline uint8_t mavlink_msg_uavcan_node_info_get_hw_version_major(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 96); -} - -/** - * @brief Get field hw_version_minor from uavcan_node_info message - * - * @return Hardware minor version number. - */ -static inline uint8_t mavlink_msg_uavcan_node_info_get_hw_version_minor(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 97); -} - -/** - * @brief Get field hw_unique_id from uavcan_node_info message - * - * @return Hardware unique 128-bit ID. - */ -static inline uint16_t mavlink_msg_uavcan_node_info_get_hw_unique_id(const mavlink_message_t* msg, uint8_t *hw_unique_id) -{ - return _MAV_RETURN_uint8_t_array(msg, hw_unique_id, 16, 98); -} - -/** - * @brief Get field sw_version_major from uavcan_node_info message - * - * @return Software major version number. - */ -static inline uint8_t mavlink_msg_uavcan_node_info_get_sw_version_major(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 114); -} - -/** - * @brief Get field sw_version_minor from uavcan_node_info message - * - * @return Software minor version number. - */ -static inline uint8_t mavlink_msg_uavcan_node_info_get_sw_version_minor(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 115); -} - -/** - * @brief Get field sw_vcs_commit from uavcan_node_info message - * - * @return Version control system (VCS) revision identifier (e.g. git short commit hash). 0 if unknown. - */ -static inline uint32_t mavlink_msg_uavcan_node_info_get_sw_vcs_commit(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 12); -} - -/** - * @brief Decode a uavcan_node_info message into a struct - * - * @param msg The message to decode - * @param uavcan_node_info C-struct to decode the message contents into - */ -static inline void mavlink_msg_uavcan_node_info_decode(const mavlink_message_t* msg, mavlink_uavcan_node_info_t* uavcan_node_info) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - uavcan_node_info->time_usec = mavlink_msg_uavcan_node_info_get_time_usec(msg); - uavcan_node_info->uptime_sec = mavlink_msg_uavcan_node_info_get_uptime_sec(msg); - uavcan_node_info->sw_vcs_commit = mavlink_msg_uavcan_node_info_get_sw_vcs_commit(msg); - mavlink_msg_uavcan_node_info_get_name(msg, uavcan_node_info->name); - uavcan_node_info->hw_version_major = mavlink_msg_uavcan_node_info_get_hw_version_major(msg); - uavcan_node_info->hw_version_minor = mavlink_msg_uavcan_node_info_get_hw_version_minor(msg); - mavlink_msg_uavcan_node_info_get_hw_unique_id(msg, uavcan_node_info->hw_unique_id); - uavcan_node_info->sw_version_major = mavlink_msg_uavcan_node_info_get_sw_version_major(msg); - uavcan_node_info->sw_version_minor = mavlink_msg_uavcan_node_info_get_sw_version_minor(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_UAVCAN_NODE_INFO_LEN? msg->len : MAVLINK_MSG_ID_UAVCAN_NODE_INFO_LEN; - memset(uavcan_node_info, 0, MAVLINK_MSG_ID_UAVCAN_NODE_INFO_LEN); - memcpy(uavcan_node_info, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_uavcan_node_status.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_uavcan_node_status.h deleted file mode 100644 index 50e3af6e..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_uavcan_node_status.h +++ /dev/null @@ -1,338 +0,0 @@ -#pragma once -// MESSAGE UAVCAN_NODE_STATUS PACKING - -#define MAVLINK_MSG_ID_UAVCAN_NODE_STATUS 310 - - -typedef struct __mavlink_uavcan_node_status_t { - uint64_t time_usec; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/ - uint32_t uptime_sec; /*< [s] Time since the start-up of the node.*/ - uint16_t vendor_specific_status_code; /*< Vendor-specific status information.*/ - uint8_t health; /*< Generalized node health status.*/ - uint8_t mode; /*< Generalized operating mode.*/ - uint8_t sub_mode; /*< Not used currently.*/ -} mavlink_uavcan_node_status_t; - -#define MAVLINK_MSG_ID_UAVCAN_NODE_STATUS_LEN 17 -#define MAVLINK_MSG_ID_UAVCAN_NODE_STATUS_MIN_LEN 17 -#define MAVLINK_MSG_ID_310_LEN 17 -#define MAVLINK_MSG_ID_310_MIN_LEN 17 - -#define MAVLINK_MSG_ID_UAVCAN_NODE_STATUS_CRC 28 -#define MAVLINK_MSG_ID_310_CRC 28 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_UAVCAN_NODE_STATUS { \ - 310, \ - "UAVCAN_NODE_STATUS", \ - 6, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_uavcan_node_status_t, time_usec) }, \ - { "uptime_sec", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_uavcan_node_status_t, uptime_sec) }, \ - { "health", NULL, MAVLINK_TYPE_UINT8_T, 0, 14, offsetof(mavlink_uavcan_node_status_t, health) }, \ - { "mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 15, offsetof(mavlink_uavcan_node_status_t, mode) }, \ - { "sub_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_uavcan_node_status_t, sub_mode) }, \ - { "vendor_specific_status_code", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_uavcan_node_status_t, vendor_specific_status_code) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_UAVCAN_NODE_STATUS { \ - "UAVCAN_NODE_STATUS", \ - 6, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_uavcan_node_status_t, time_usec) }, \ - { "uptime_sec", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_uavcan_node_status_t, uptime_sec) }, \ - { "health", NULL, MAVLINK_TYPE_UINT8_T, 0, 14, offsetof(mavlink_uavcan_node_status_t, health) }, \ - { "mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 15, offsetof(mavlink_uavcan_node_status_t, mode) }, \ - { "sub_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_uavcan_node_status_t, sub_mode) }, \ - { "vendor_specific_status_code", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_uavcan_node_status_t, vendor_specific_status_code) }, \ - } \ -} -#endif - -/** - * @brief Pack a uavcan_node_status message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @param uptime_sec [s] Time since the start-up of the node. - * @param health Generalized node health status. - * @param mode Generalized operating mode. - * @param sub_mode Not used currently. - * @param vendor_specific_status_code Vendor-specific status information. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_uavcan_node_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint64_t time_usec, uint32_t uptime_sec, uint8_t health, uint8_t mode, uint8_t sub_mode, uint16_t vendor_specific_status_code) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_UAVCAN_NODE_STATUS_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint32_t(buf, 8, uptime_sec); - _mav_put_uint16_t(buf, 12, vendor_specific_status_code); - _mav_put_uint8_t(buf, 14, health); - _mav_put_uint8_t(buf, 15, mode); - _mav_put_uint8_t(buf, 16, sub_mode); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_UAVCAN_NODE_STATUS_LEN); -#else - mavlink_uavcan_node_status_t packet; - packet.time_usec = time_usec; - packet.uptime_sec = uptime_sec; - packet.vendor_specific_status_code = vendor_specific_status_code; - packet.health = health; - packet.mode = mode; - packet.sub_mode = sub_mode; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_UAVCAN_NODE_STATUS_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_UAVCAN_NODE_STATUS; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_UAVCAN_NODE_STATUS_MIN_LEN, MAVLINK_MSG_ID_UAVCAN_NODE_STATUS_LEN, MAVLINK_MSG_ID_UAVCAN_NODE_STATUS_CRC); -} - -/** - * @brief Pack a uavcan_node_status message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @param uptime_sec [s] Time since the start-up of the node. - * @param health Generalized node health status. - * @param mode Generalized operating mode. - * @param sub_mode Not used currently. - * @param vendor_specific_status_code Vendor-specific status information. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_uavcan_node_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint64_t time_usec,uint32_t uptime_sec,uint8_t health,uint8_t mode,uint8_t sub_mode,uint16_t vendor_specific_status_code) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_UAVCAN_NODE_STATUS_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint32_t(buf, 8, uptime_sec); - _mav_put_uint16_t(buf, 12, vendor_specific_status_code); - _mav_put_uint8_t(buf, 14, health); - _mav_put_uint8_t(buf, 15, mode); - _mav_put_uint8_t(buf, 16, sub_mode); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_UAVCAN_NODE_STATUS_LEN); -#else - mavlink_uavcan_node_status_t packet; - packet.time_usec = time_usec; - packet.uptime_sec = uptime_sec; - packet.vendor_specific_status_code = vendor_specific_status_code; - packet.health = health; - packet.mode = mode; - packet.sub_mode = sub_mode; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_UAVCAN_NODE_STATUS_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_UAVCAN_NODE_STATUS; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_UAVCAN_NODE_STATUS_MIN_LEN, MAVLINK_MSG_ID_UAVCAN_NODE_STATUS_LEN, MAVLINK_MSG_ID_UAVCAN_NODE_STATUS_CRC); -} - -/** - * @brief Encode a uavcan_node_status struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param uavcan_node_status C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_uavcan_node_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_uavcan_node_status_t* uavcan_node_status) -{ - return mavlink_msg_uavcan_node_status_pack(system_id, component_id, msg, uavcan_node_status->time_usec, uavcan_node_status->uptime_sec, uavcan_node_status->health, uavcan_node_status->mode, uavcan_node_status->sub_mode, uavcan_node_status->vendor_specific_status_code); -} - -/** - * @brief Encode a uavcan_node_status struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param uavcan_node_status C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_uavcan_node_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_uavcan_node_status_t* uavcan_node_status) -{ - return mavlink_msg_uavcan_node_status_pack_chan(system_id, component_id, chan, msg, uavcan_node_status->time_usec, uavcan_node_status->uptime_sec, uavcan_node_status->health, uavcan_node_status->mode, uavcan_node_status->sub_mode, uavcan_node_status->vendor_specific_status_code); -} - -/** - * @brief Send a uavcan_node_status message - * @param chan MAVLink channel to send the message - * - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @param uptime_sec [s] Time since the start-up of the node. - * @param health Generalized node health status. - * @param mode Generalized operating mode. - * @param sub_mode Not used currently. - * @param vendor_specific_status_code Vendor-specific status information. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_uavcan_node_status_send(mavlink_channel_t chan, uint64_t time_usec, uint32_t uptime_sec, uint8_t health, uint8_t mode, uint8_t sub_mode, uint16_t vendor_specific_status_code) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_UAVCAN_NODE_STATUS_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint32_t(buf, 8, uptime_sec); - _mav_put_uint16_t(buf, 12, vendor_specific_status_code); - _mav_put_uint8_t(buf, 14, health); - _mav_put_uint8_t(buf, 15, mode); - _mav_put_uint8_t(buf, 16, sub_mode); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_UAVCAN_NODE_STATUS, buf, MAVLINK_MSG_ID_UAVCAN_NODE_STATUS_MIN_LEN, MAVLINK_MSG_ID_UAVCAN_NODE_STATUS_LEN, MAVLINK_MSG_ID_UAVCAN_NODE_STATUS_CRC); -#else - mavlink_uavcan_node_status_t packet; - packet.time_usec = time_usec; - packet.uptime_sec = uptime_sec; - packet.vendor_specific_status_code = vendor_specific_status_code; - packet.health = health; - packet.mode = mode; - packet.sub_mode = sub_mode; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_UAVCAN_NODE_STATUS, (const char *)&packet, MAVLINK_MSG_ID_UAVCAN_NODE_STATUS_MIN_LEN, MAVLINK_MSG_ID_UAVCAN_NODE_STATUS_LEN, MAVLINK_MSG_ID_UAVCAN_NODE_STATUS_CRC); -#endif -} - -/** - * @brief Send a uavcan_node_status message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_uavcan_node_status_send_struct(mavlink_channel_t chan, const mavlink_uavcan_node_status_t* uavcan_node_status) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_uavcan_node_status_send(chan, uavcan_node_status->time_usec, uavcan_node_status->uptime_sec, uavcan_node_status->health, uavcan_node_status->mode, uavcan_node_status->sub_mode, uavcan_node_status->vendor_specific_status_code); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_UAVCAN_NODE_STATUS, (const char *)uavcan_node_status, MAVLINK_MSG_ID_UAVCAN_NODE_STATUS_MIN_LEN, MAVLINK_MSG_ID_UAVCAN_NODE_STATUS_LEN, MAVLINK_MSG_ID_UAVCAN_NODE_STATUS_CRC); -#endif -} - -#if MAVLINK_MSG_ID_UAVCAN_NODE_STATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_uavcan_node_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, uint32_t uptime_sec, uint8_t health, uint8_t mode, uint8_t sub_mode, uint16_t vendor_specific_status_code) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint32_t(buf, 8, uptime_sec); - _mav_put_uint16_t(buf, 12, vendor_specific_status_code); - _mav_put_uint8_t(buf, 14, health); - _mav_put_uint8_t(buf, 15, mode); - _mav_put_uint8_t(buf, 16, sub_mode); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_UAVCAN_NODE_STATUS, buf, MAVLINK_MSG_ID_UAVCAN_NODE_STATUS_MIN_LEN, MAVLINK_MSG_ID_UAVCAN_NODE_STATUS_LEN, MAVLINK_MSG_ID_UAVCAN_NODE_STATUS_CRC); -#else - mavlink_uavcan_node_status_t *packet = (mavlink_uavcan_node_status_t *)msgbuf; - packet->time_usec = time_usec; - packet->uptime_sec = uptime_sec; - packet->vendor_specific_status_code = vendor_specific_status_code; - packet->health = health; - packet->mode = mode; - packet->sub_mode = sub_mode; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_UAVCAN_NODE_STATUS, (const char *)packet, MAVLINK_MSG_ID_UAVCAN_NODE_STATUS_MIN_LEN, MAVLINK_MSG_ID_UAVCAN_NODE_STATUS_LEN, MAVLINK_MSG_ID_UAVCAN_NODE_STATUS_CRC); -#endif -} -#endif - -#endif - -// MESSAGE UAVCAN_NODE_STATUS UNPACKING - - -/** - * @brief Get field time_usec from uavcan_node_status message - * - * @return [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - */ -static inline uint64_t mavlink_msg_uavcan_node_status_get_time_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field uptime_sec from uavcan_node_status message - * - * @return [s] Time since the start-up of the node. - */ -static inline uint32_t mavlink_msg_uavcan_node_status_get_uptime_sec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 8); -} - -/** - * @brief Get field health from uavcan_node_status message - * - * @return Generalized node health status. - */ -static inline uint8_t mavlink_msg_uavcan_node_status_get_health(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 14); -} - -/** - * @brief Get field mode from uavcan_node_status message - * - * @return Generalized operating mode. - */ -static inline uint8_t mavlink_msg_uavcan_node_status_get_mode(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 15); -} - -/** - * @brief Get field sub_mode from uavcan_node_status message - * - * @return Not used currently. - */ -static inline uint8_t mavlink_msg_uavcan_node_status_get_sub_mode(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 16); -} - -/** - * @brief Get field vendor_specific_status_code from uavcan_node_status message - * - * @return Vendor-specific status information. - */ -static inline uint16_t mavlink_msg_uavcan_node_status_get_vendor_specific_status_code(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 12); -} - -/** - * @brief Decode a uavcan_node_status message into a struct - * - * @param msg The message to decode - * @param uavcan_node_status C-struct to decode the message contents into - */ -static inline void mavlink_msg_uavcan_node_status_decode(const mavlink_message_t* msg, mavlink_uavcan_node_status_t* uavcan_node_status) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - uavcan_node_status->time_usec = mavlink_msg_uavcan_node_status_get_time_usec(msg); - uavcan_node_status->uptime_sec = mavlink_msg_uavcan_node_status_get_uptime_sec(msg); - uavcan_node_status->vendor_specific_status_code = mavlink_msg_uavcan_node_status_get_vendor_specific_status_code(msg); - uavcan_node_status->health = mavlink_msg_uavcan_node_status_get_health(msg); - uavcan_node_status->mode = mavlink_msg_uavcan_node_status_get_mode(msg); - uavcan_node_status->sub_mode = mavlink_msg_uavcan_node_status_get_sub_mode(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_UAVCAN_NODE_STATUS_LEN? msg->len : MAVLINK_MSG_ID_UAVCAN_NODE_STATUS_LEN; - memset(uavcan_node_status, 0, MAVLINK_MSG_ID_UAVCAN_NODE_STATUS_LEN); - memcpy(uavcan_node_status, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_utm_global_position.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_utm_global_position.h deleted file mode 100644 index 587f7bb6..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_utm_global_position.h +++ /dev/null @@ -1,630 +0,0 @@ -#pragma once -// MESSAGE UTM_GLOBAL_POSITION PACKING - -#define MAVLINK_MSG_ID_UTM_GLOBAL_POSITION 340 - - -typedef struct __mavlink_utm_global_position_t { - uint64_t time; /*< [us] Time of applicability of position (microseconds since UNIX epoch).*/ - int32_t lat; /*< [degE7] Latitude (WGS84)*/ - int32_t lon; /*< [degE7] Longitude (WGS84)*/ - int32_t alt; /*< [mm] Altitude (WGS84)*/ - int32_t relative_alt; /*< [mm] Altitude above ground*/ - int32_t next_lat; /*< [degE7] Next waypoint, latitude (WGS84)*/ - int32_t next_lon; /*< [degE7] Next waypoint, longitude (WGS84)*/ - int32_t next_alt; /*< [mm] Next waypoint, altitude (WGS84)*/ - int16_t vx; /*< [cm/s] Ground X speed (latitude, positive north)*/ - int16_t vy; /*< [cm/s] Ground Y speed (longitude, positive east)*/ - int16_t vz; /*< [cm/s] Ground Z speed (altitude, positive down)*/ - uint16_t h_acc; /*< [mm] Horizontal position uncertainty (standard deviation)*/ - uint16_t v_acc; /*< [mm] Altitude uncertainty (standard deviation)*/ - uint16_t vel_acc; /*< [cm/s] Speed uncertainty (standard deviation)*/ - uint16_t update_rate; /*< [cs] Time until next update. Set to 0 if unknown or in data driven mode.*/ - uint8_t uas_id[18]; /*< Unique UAS ID.*/ - uint8_t flight_state; /*< Flight state*/ - uint8_t flags; /*< Bitwise OR combination of the data available flags.*/ -} mavlink_utm_global_position_t; - -#define MAVLINK_MSG_ID_UTM_GLOBAL_POSITION_LEN 70 -#define MAVLINK_MSG_ID_UTM_GLOBAL_POSITION_MIN_LEN 70 -#define MAVLINK_MSG_ID_340_LEN 70 -#define MAVLINK_MSG_ID_340_MIN_LEN 70 - -#define MAVLINK_MSG_ID_UTM_GLOBAL_POSITION_CRC 99 -#define MAVLINK_MSG_ID_340_CRC 99 - -#define MAVLINK_MSG_UTM_GLOBAL_POSITION_FIELD_UAS_ID_LEN 18 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_UTM_GLOBAL_POSITION { \ - 340, \ - "UTM_GLOBAL_POSITION", \ - 18, \ - { { "time", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_utm_global_position_t, time) }, \ - { "uas_id", NULL, MAVLINK_TYPE_UINT8_T, 18, 50, offsetof(mavlink_utm_global_position_t, uas_id) }, \ - { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_utm_global_position_t, lat) }, \ - { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_utm_global_position_t, lon) }, \ - { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_utm_global_position_t, alt) }, \ - { "relative_alt", NULL, MAVLINK_TYPE_INT32_T, 0, 20, offsetof(mavlink_utm_global_position_t, relative_alt) }, \ - { "vx", NULL, MAVLINK_TYPE_INT16_T, 0, 36, offsetof(mavlink_utm_global_position_t, vx) }, \ - { "vy", NULL, MAVLINK_TYPE_INT16_T, 0, 38, offsetof(mavlink_utm_global_position_t, vy) }, \ - { "vz", NULL, MAVLINK_TYPE_INT16_T, 0, 40, offsetof(mavlink_utm_global_position_t, vz) }, \ - { "h_acc", NULL, MAVLINK_TYPE_UINT16_T, 0, 42, offsetof(mavlink_utm_global_position_t, h_acc) }, \ - { "v_acc", NULL, MAVLINK_TYPE_UINT16_T, 0, 44, offsetof(mavlink_utm_global_position_t, v_acc) }, \ - { "vel_acc", NULL, MAVLINK_TYPE_UINT16_T, 0, 46, offsetof(mavlink_utm_global_position_t, vel_acc) }, \ - { "next_lat", NULL, MAVLINK_TYPE_INT32_T, 0, 24, offsetof(mavlink_utm_global_position_t, next_lat) }, \ - { "next_lon", NULL, MAVLINK_TYPE_INT32_T, 0, 28, offsetof(mavlink_utm_global_position_t, next_lon) }, \ - { "next_alt", NULL, MAVLINK_TYPE_INT32_T, 0, 32, offsetof(mavlink_utm_global_position_t, next_alt) }, \ - { "update_rate", NULL, MAVLINK_TYPE_UINT16_T, 0, 48, offsetof(mavlink_utm_global_position_t, update_rate) }, \ - { "flight_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 68, offsetof(mavlink_utm_global_position_t, flight_state) }, \ - { "flags", NULL, MAVLINK_TYPE_UINT8_T, 0, 69, offsetof(mavlink_utm_global_position_t, flags) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_UTM_GLOBAL_POSITION { \ - "UTM_GLOBAL_POSITION", \ - 18, \ - { { "time", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_utm_global_position_t, time) }, \ - { "uas_id", NULL, MAVLINK_TYPE_UINT8_T, 18, 50, offsetof(mavlink_utm_global_position_t, uas_id) }, \ - { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_utm_global_position_t, lat) }, \ - { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_utm_global_position_t, lon) }, \ - { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_utm_global_position_t, alt) }, \ - { "relative_alt", NULL, MAVLINK_TYPE_INT32_T, 0, 20, offsetof(mavlink_utm_global_position_t, relative_alt) }, \ - { "vx", NULL, MAVLINK_TYPE_INT16_T, 0, 36, offsetof(mavlink_utm_global_position_t, vx) }, \ - { "vy", NULL, MAVLINK_TYPE_INT16_T, 0, 38, offsetof(mavlink_utm_global_position_t, vy) }, \ - { "vz", NULL, MAVLINK_TYPE_INT16_T, 0, 40, offsetof(mavlink_utm_global_position_t, vz) }, \ - { "h_acc", NULL, MAVLINK_TYPE_UINT16_T, 0, 42, offsetof(mavlink_utm_global_position_t, h_acc) }, \ - { "v_acc", NULL, MAVLINK_TYPE_UINT16_T, 0, 44, offsetof(mavlink_utm_global_position_t, v_acc) }, \ - { "vel_acc", NULL, MAVLINK_TYPE_UINT16_T, 0, 46, offsetof(mavlink_utm_global_position_t, vel_acc) }, \ - { "next_lat", NULL, MAVLINK_TYPE_INT32_T, 0, 24, offsetof(mavlink_utm_global_position_t, next_lat) }, \ - { "next_lon", NULL, MAVLINK_TYPE_INT32_T, 0, 28, offsetof(mavlink_utm_global_position_t, next_lon) }, \ - { "next_alt", NULL, MAVLINK_TYPE_INT32_T, 0, 32, offsetof(mavlink_utm_global_position_t, next_alt) }, \ - { "update_rate", NULL, MAVLINK_TYPE_UINT16_T, 0, 48, offsetof(mavlink_utm_global_position_t, update_rate) }, \ - { "flight_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 68, offsetof(mavlink_utm_global_position_t, flight_state) }, \ - { "flags", NULL, MAVLINK_TYPE_UINT8_T, 0, 69, offsetof(mavlink_utm_global_position_t, flags) }, \ - } \ -} -#endif - -/** - * @brief Pack a utm_global_position message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param time [us] Time of applicability of position (microseconds since UNIX epoch). - * @param uas_id Unique UAS ID. - * @param lat [degE7] Latitude (WGS84) - * @param lon [degE7] Longitude (WGS84) - * @param alt [mm] Altitude (WGS84) - * @param relative_alt [mm] Altitude above ground - * @param vx [cm/s] Ground X speed (latitude, positive north) - * @param vy [cm/s] Ground Y speed (longitude, positive east) - * @param vz [cm/s] Ground Z speed (altitude, positive down) - * @param h_acc [mm] Horizontal position uncertainty (standard deviation) - * @param v_acc [mm] Altitude uncertainty (standard deviation) - * @param vel_acc [cm/s] Speed uncertainty (standard deviation) - * @param next_lat [degE7] Next waypoint, latitude (WGS84) - * @param next_lon [degE7] Next waypoint, longitude (WGS84) - * @param next_alt [mm] Next waypoint, altitude (WGS84) - * @param update_rate [cs] Time until next update. Set to 0 if unknown or in data driven mode. - * @param flight_state Flight state - * @param flags Bitwise OR combination of the data available flags. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_utm_global_position_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint64_t time, const uint8_t *uas_id, int32_t lat, int32_t lon, int32_t alt, int32_t relative_alt, int16_t vx, int16_t vy, int16_t vz, uint16_t h_acc, uint16_t v_acc, uint16_t vel_acc, int32_t next_lat, int32_t next_lon, int32_t next_alt, uint16_t update_rate, uint8_t flight_state, uint8_t flags) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_UTM_GLOBAL_POSITION_LEN]; - _mav_put_uint64_t(buf, 0, time); - _mav_put_int32_t(buf, 8, lat); - _mav_put_int32_t(buf, 12, lon); - _mav_put_int32_t(buf, 16, alt); - _mav_put_int32_t(buf, 20, relative_alt); - _mav_put_int32_t(buf, 24, next_lat); - _mav_put_int32_t(buf, 28, next_lon); - _mav_put_int32_t(buf, 32, next_alt); - _mav_put_int16_t(buf, 36, vx); - _mav_put_int16_t(buf, 38, vy); - _mav_put_int16_t(buf, 40, vz); - _mav_put_uint16_t(buf, 42, h_acc); - _mav_put_uint16_t(buf, 44, v_acc); - _mav_put_uint16_t(buf, 46, vel_acc); - _mav_put_uint16_t(buf, 48, update_rate); - _mav_put_uint8_t(buf, 68, flight_state); - _mav_put_uint8_t(buf, 69, flags); - _mav_put_uint8_t_array(buf, 50, uas_id, 18); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_UTM_GLOBAL_POSITION_LEN); -#else - mavlink_utm_global_position_t packet; - packet.time = time; - packet.lat = lat; - packet.lon = lon; - packet.alt = alt; - packet.relative_alt = relative_alt; - packet.next_lat = next_lat; - packet.next_lon = next_lon; - packet.next_alt = next_alt; - packet.vx = vx; - packet.vy = vy; - packet.vz = vz; - packet.h_acc = h_acc; - packet.v_acc = v_acc; - packet.vel_acc = vel_acc; - packet.update_rate = update_rate; - packet.flight_state = flight_state; - packet.flags = flags; - mav_array_memcpy(packet.uas_id, uas_id, sizeof(uint8_t)*18); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_UTM_GLOBAL_POSITION_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_UTM_GLOBAL_POSITION; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_UTM_GLOBAL_POSITION_MIN_LEN, MAVLINK_MSG_ID_UTM_GLOBAL_POSITION_LEN, MAVLINK_MSG_ID_UTM_GLOBAL_POSITION_CRC); -} - -/** - * @brief Pack a utm_global_position message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time [us] Time of applicability of position (microseconds since UNIX epoch). - * @param uas_id Unique UAS ID. - * @param lat [degE7] Latitude (WGS84) - * @param lon [degE7] Longitude (WGS84) - * @param alt [mm] Altitude (WGS84) - * @param relative_alt [mm] Altitude above ground - * @param vx [cm/s] Ground X speed (latitude, positive north) - * @param vy [cm/s] Ground Y speed (longitude, positive east) - * @param vz [cm/s] Ground Z speed (altitude, positive down) - * @param h_acc [mm] Horizontal position uncertainty (standard deviation) - * @param v_acc [mm] Altitude uncertainty (standard deviation) - * @param vel_acc [cm/s] Speed uncertainty (standard deviation) - * @param next_lat [degE7] Next waypoint, latitude (WGS84) - * @param next_lon [degE7] Next waypoint, longitude (WGS84) - * @param next_alt [mm] Next waypoint, altitude (WGS84) - * @param update_rate [cs] Time until next update. Set to 0 if unknown or in data driven mode. - * @param flight_state Flight state - * @param flags Bitwise OR combination of the data available flags. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_utm_global_position_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint64_t time,const uint8_t *uas_id,int32_t lat,int32_t lon,int32_t alt,int32_t relative_alt,int16_t vx,int16_t vy,int16_t vz,uint16_t h_acc,uint16_t v_acc,uint16_t vel_acc,int32_t next_lat,int32_t next_lon,int32_t next_alt,uint16_t update_rate,uint8_t flight_state,uint8_t flags) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_UTM_GLOBAL_POSITION_LEN]; - _mav_put_uint64_t(buf, 0, time); - _mav_put_int32_t(buf, 8, lat); - _mav_put_int32_t(buf, 12, lon); - _mav_put_int32_t(buf, 16, alt); - _mav_put_int32_t(buf, 20, relative_alt); - _mav_put_int32_t(buf, 24, next_lat); - _mav_put_int32_t(buf, 28, next_lon); - _mav_put_int32_t(buf, 32, next_alt); - _mav_put_int16_t(buf, 36, vx); - _mav_put_int16_t(buf, 38, vy); - _mav_put_int16_t(buf, 40, vz); - _mav_put_uint16_t(buf, 42, h_acc); - _mav_put_uint16_t(buf, 44, v_acc); - _mav_put_uint16_t(buf, 46, vel_acc); - _mav_put_uint16_t(buf, 48, update_rate); - _mav_put_uint8_t(buf, 68, flight_state); - _mav_put_uint8_t(buf, 69, flags); - _mav_put_uint8_t_array(buf, 50, uas_id, 18); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_UTM_GLOBAL_POSITION_LEN); -#else - mavlink_utm_global_position_t packet; - packet.time = time; - packet.lat = lat; - packet.lon = lon; - packet.alt = alt; - packet.relative_alt = relative_alt; - packet.next_lat = next_lat; - packet.next_lon = next_lon; - packet.next_alt = next_alt; - packet.vx = vx; - packet.vy = vy; - packet.vz = vz; - packet.h_acc = h_acc; - packet.v_acc = v_acc; - packet.vel_acc = vel_acc; - packet.update_rate = update_rate; - packet.flight_state = flight_state; - packet.flags = flags; - mav_array_memcpy(packet.uas_id, uas_id, sizeof(uint8_t)*18); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_UTM_GLOBAL_POSITION_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_UTM_GLOBAL_POSITION; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_UTM_GLOBAL_POSITION_MIN_LEN, MAVLINK_MSG_ID_UTM_GLOBAL_POSITION_LEN, MAVLINK_MSG_ID_UTM_GLOBAL_POSITION_CRC); -} - -/** - * @brief Encode a utm_global_position struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param utm_global_position C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_utm_global_position_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_utm_global_position_t* utm_global_position) -{ - return mavlink_msg_utm_global_position_pack(system_id, component_id, msg, utm_global_position->time, utm_global_position->uas_id, utm_global_position->lat, utm_global_position->lon, utm_global_position->alt, utm_global_position->relative_alt, utm_global_position->vx, utm_global_position->vy, utm_global_position->vz, utm_global_position->h_acc, utm_global_position->v_acc, utm_global_position->vel_acc, utm_global_position->next_lat, utm_global_position->next_lon, utm_global_position->next_alt, utm_global_position->update_rate, utm_global_position->flight_state, utm_global_position->flags); -} - -/** - * @brief Encode a utm_global_position struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param utm_global_position C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_utm_global_position_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_utm_global_position_t* utm_global_position) -{ - return mavlink_msg_utm_global_position_pack_chan(system_id, component_id, chan, msg, utm_global_position->time, utm_global_position->uas_id, utm_global_position->lat, utm_global_position->lon, utm_global_position->alt, utm_global_position->relative_alt, utm_global_position->vx, utm_global_position->vy, utm_global_position->vz, utm_global_position->h_acc, utm_global_position->v_acc, utm_global_position->vel_acc, utm_global_position->next_lat, utm_global_position->next_lon, utm_global_position->next_alt, utm_global_position->update_rate, utm_global_position->flight_state, utm_global_position->flags); -} - -/** - * @brief Send a utm_global_position message - * @param chan MAVLink channel to send the message - * - * @param time [us] Time of applicability of position (microseconds since UNIX epoch). - * @param uas_id Unique UAS ID. - * @param lat [degE7] Latitude (WGS84) - * @param lon [degE7] Longitude (WGS84) - * @param alt [mm] Altitude (WGS84) - * @param relative_alt [mm] Altitude above ground - * @param vx [cm/s] Ground X speed (latitude, positive north) - * @param vy [cm/s] Ground Y speed (longitude, positive east) - * @param vz [cm/s] Ground Z speed (altitude, positive down) - * @param h_acc [mm] Horizontal position uncertainty (standard deviation) - * @param v_acc [mm] Altitude uncertainty (standard deviation) - * @param vel_acc [cm/s] Speed uncertainty (standard deviation) - * @param next_lat [degE7] Next waypoint, latitude (WGS84) - * @param next_lon [degE7] Next waypoint, longitude (WGS84) - * @param next_alt [mm] Next waypoint, altitude (WGS84) - * @param update_rate [cs] Time until next update. Set to 0 if unknown or in data driven mode. - * @param flight_state Flight state - * @param flags Bitwise OR combination of the data available flags. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_utm_global_position_send(mavlink_channel_t chan, uint64_t time, const uint8_t *uas_id, int32_t lat, int32_t lon, int32_t alt, int32_t relative_alt, int16_t vx, int16_t vy, int16_t vz, uint16_t h_acc, uint16_t v_acc, uint16_t vel_acc, int32_t next_lat, int32_t next_lon, int32_t next_alt, uint16_t update_rate, uint8_t flight_state, uint8_t flags) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_UTM_GLOBAL_POSITION_LEN]; - _mav_put_uint64_t(buf, 0, time); - _mav_put_int32_t(buf, 8, lat); - _mav_put_int32_t(buf, 12, lon); - _mav_put_int32_t(buf, 16, alt); - _mav_put_int32_t(buf, 20, relative_alt); - _mav_put_int32_t(buf, 24, next_lat); - _mav_put_int32_t(buf, 28, next_lon); - _mav_put_int32_t(buf, 32, next_alt); - _mav_put_int16_t(buf, 36, vx); - _mav_put_int16_t(buf, 38, vy); - _mav_put_int16_t(buf, 40, vz); - _mav_put_uint16_t(buf, 42, h_acc); - _mav_put_uint16_t(buf, 44, v_acc); - _mav_put_uint16_t(buf, 46, vel_acc); - _mav_put_uint16_t(buf, 48, update_rate); - _mav_put_uint8_t(buf, 68, flight_state); - _mav_put_uint8_t(buf, 69, flags); - _mav_put_uint8_t_array(buf, 50, uas_id, 18); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_UTM_GLOBAL_POSITION, buf, MAVLINK_MSG_ID_UTM_GLOBAL_POSITION_MIN_LEN, MAVLINK_MSG_ID_UTM_GLOBAL_POSITION_LEN, MAVLINK_MSG_ID_UTM_GLOBAL_POSITION_CRC); -#else - mavlink_utm_global_position_t packet; - packet.time = time; - packet.lat = lat; - packet.lon = lon; - packet.alt = alt; - packet.relative_alt = relative_alt; - packet.next_lat = next_lat; - packet.next_lon = next_lon; - packet.next_alt = next_alt; - packet.vx = vx; - packet.vy = vy; - packet.vz = vz; - packet.h_acc = h_acc; - packet.v_acc = v_acc; - packet.vel_acc = vel_acc; - packet.update_rate = update_rate; - packet.flight_state = flight_state; - packet.flags = flags; - mav_array_memcpy(packet.uas_id, uas_id, sizeof(uint8_t)*18); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_UTM_GLOBAL_POSITION, (const char *)&packet, MAVLINK_MSG_ID_UTM_GLOBAL_POSITION_MIN_LEN, MAVLINK_MSG_ID_UTM_GLOBAL_POSITION_LEN, MAVLINK_MSG_ID_UTM_GLOBAL_POSITION_CRC); -#endif -} - -/** - * @brief Send a utm_global_position message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_utm_global_position_send_struct(mavlink_channel_t chan, const mavlink_utm_global_position_t* utm_global_position) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_utm_global_position_send(chan, utm_global_position->time, utm_global_position->uas_id, utm_global_position->lat, utm_global_position->lon, utm_global_position->alt, utm_global_position->relative_alt, utm_global_position->vx, utm_global_position->vy, utm_global_position->vz, utm_global_position->h_acc, utm_global_position->v_acc, utm_global_position->vel_acc, utm_global_position->next_lat, utm_global_position->next_lon, utm_global_position->next_alt, utm_global_position->update_rate, utm_global_position->flight_state, utm_global_position->flags); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_UTM_GLOBAL_POSITION, (const char *)utm_global_position, MAVLINK_MSG_ID_UTM_GLOBAL_POSITION_MIN_LEN, MAVLINK_MSG_ID_UTM_GLOBAL_POSITION_LEN, MAVLINK_MSG_ID_UTM_GLOBAL_POSITION_CRC); -#endif -} - -#if MAVLINK_MSG_ID_UTM_GLOBAL_POSITION_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_utm_global_position_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time, const uint8_t *uas_id, int32_t lat, int32_t lon, int32_t alt, int32_t relative_alt, int16_t vx, int16_t vy, int16_t vz, uint16_t h_acc, uint16_t v_acc, uint16_t vel_acc, int32_t next_lat, int32_t next_lon, int32_t next_alt, uint16_t update_rate, uint8_t flight_state, uint8_t flags) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, time); - _mav_put_int32_t(buf, 8, lat); - _mav_put_int32_t(buf, 12, lon); - _mav_put_int32_t(buf, 16, alt); - _mav_put_int32_t(buf, 20, relative_alt); - _mav_put_int32_t(buf, 24, next_lat); - _mav_put_int32_t(buf, 28, next_lon); - _mav_put_int32_t(buf, 32, next_alt); - _mav_put_int16_t(buf, 36, vx); - _mav_put_int16_t(buf, 38, vy); - _mav_put_int16_t(buf, 40, vz); - _mav_put_uint16_t(buf, 42, h_acc); - _mav_put_uint16_t(buf, 44, v_acc); - _mav_put_uint16_t(buf, 46, vel_acc); - _mav_put_uint16_t(buf, 48, update_rate); - _mav_put_uint8_t(buf, 68, flight_state); - _mav_put_uint8_t(buf, 69, flags); - _mav_put_uint8_t_array(buf, 50, uas_id, 18); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_UTM_GLOBAL_POSITION, buf, MAVLINK_MSG_ID_UTM_GLOBAL_POSITION_MIN_LEN, MAVLINK_MSG_ID_UTM_GLOBAL_POSITION_LEN, MAVLINK_MSG_ID_UTM_GLOBAL_POSITION_CRC); -#else - mavlink_utm_global_position_t *packet = (mavlink_utm_global_position_t *)msgbuf; - packet->time = time; - packet->lat = lat; - packet->lon = lon; - packet->alt = alt; - packet->relative_alt = relative_alt; - packet->next_lat = next_lat; - packet->next_lon = next_lon; - packet->next_alt = next_alt; - packet->vx = vx; - packet->vy = vy; - packet->vz = vz; - packet->h_acc = h_acc; - packet->v_acc = v_acc; - packet->vel_acc = vel_acc; - packet->update_rate = update_rate; - packet->flight_state = flight_state; - packet->flags = flags; - mav_array_memcpy(packet->uas_id, uas_id, sizeof(uint8_t)*18); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_UTM_GLOBAL_POSITION, (const char *)packet, MAVLINK_MSG_ID_UTM_GLOBAL_POSITION_MIN_LEN, MAVLINK_MSG_ID_UTM_GLOBAL_POSITION_LEN, MAVLINK_MSG_ID_UTM_GLOBAL_POSITION_CRC); -#endif -} -#endif - -#endif - -// MESSAGE UTM_GLOBAL_POSITION UNPACKING - - -/** - * @brief Get field time from utm_global_position message - * - * @return [us] Time of applicability of position (microseconds since UNIX epoch). - */ -static inline uint64_t mavlink_msg_utm_global_position_get_time(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field uas_id from utm_global_position message - * - * @return Unique UAS ID. - */ -static inline uint16_t mavlink_msg_utm_global_position_get_uas_id(const mavlink_message_t* msg, uint8_t *uas_id) -{ - return _MAV_RETURN_uint8_t_array(msg, uas_id, 18, 50); -} - -/** - * @brief Get field lat from utm_global_position message - * - * @return [degE7] Latitude (WGS84) - */ -static inline int32_t mavlink_msg_utm_global_position_get_lat(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 8); -} - -/** - * @brief Get field lon from utm_global_position message - * - * @return [degE7] Longitude (WGS84) - */ -static inline int32_t mavlink_msg_utm_global_position_get_lon(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 12); -} - -/** - * @brief Get field alt from utm_global_position message - * - * @return [mm] Altitude (WGS84) - */ -static inline int32_t mavlink_msg_utm_global_position_get_alt(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 16); -} - -/** - * @brief Get field relative_alt from utm_global_position message - * - * @return [mm] Altitude above ground - */ -static inline int32_t mavlink_msg_utm_global_position_get_relative_alt(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 20); -} - -/** - * @brief Get field vx from utm_global_position message - * - * @return [cm/s] Ground X speed (latitude, positive north) - */ -static inline int16_t mavlink_msg_utm_global_position_get_vx(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 36); -} - -/** - * @brief Get field vy from utm_global_position message - * - * @return [cm/s] Ground Y speed (longitude, positive east) - */ -static inline int16_t mavlink_msg_utm_global_position_get_vy(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 38); -} - -/** - * @brief Get field vz from utm_global_position message - * - * @return [cm/s] Ground Z speed (altitude, positive down) - */ -static inline int16_t mavlink_msg_utm_global_position_get_vz(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 40); -} - -/** - * @brief Get field h_acc from utm_global_position message - * - * @return [mm] Horizontal position uncertainty (standard deviation) - */ -static inline uint16_t mavlink_msg_utm_global_position_get_h_acc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 42); -} - -/** - * @brief Get field v_acc from utm_global_position message - * - * @return [mm] Altitude uncertainty (standard deviation) - */ -static inline uint16_t mavlink_msg_utm_global_position_get_v_acc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 44); -} - -/** - * @brief Get field vel_acc from utm_global_position message - * - * @return [cm/s] Speed uncertainty (standard deviation) - */ -static inline uint16_t mavlink_msg_utm_global_position_get_vel_acc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 46); -} - -/** - * @brief Get field next_lat from utm_global_position message - * - * @return [degE7] Next waypoint, latitude (WGS84) - */ -static inline int32_t mavlink_msg_utm_global_position_get_next_lat(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 24); -} - -/** - * @brief Get field next_lon from utm_global_position message - * - * @return [degE7] Next waypoint, longitude (WGS84) - */ -static inline int32_t mavlink_msg_utm_global_position_get_next_lon(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 28); -} - -/** - * @brief Get field next_alt from utm_global_position message - * - * @return [mm] Next waypoint, altitude (WGS84) - */ -static inline int32_t mavlink_msg_utm_global_position_get_next_alt(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 32); -} - -/** - * @brief Get field update_rate from utm_global_position message - * - * @return [cs] Time until next update. Set to 0 if unknown or in data driven mode. - */ -static inline uint16_t mavlink_msg_utm_global_position_get_update_rate(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 48); -} - -/** - * @brief Get field flight_state from utm_global_position message - * - * @return Flight state - */ -static inline uint8_t mavlink_msg_utm_global_position_get_flight_state(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 68); -} - -/** - * @brief Get field flags from utm_global_position message - * - * @return Bitwise OR combination of the data available flags. - */ -static inline uint8_t mavlink_msg_utm_global_position_get_flags(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 69); -} - -/** - * @brief Decode a utm_global_position message into a struct - * - * @param msg The message to decode - * @param utm_global_position C-struct to decode the message contents into - */ -static inline void mavlink_msg_utm_global_position_decode(const mavlink_message_t* msg, mavlink_utm_global_position_t* utm_global_position) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - utm_global_position->time = mavlink_msg_utm_global_position_get_time(msg); - utm_global_position->lat = mavlink_msg_utm_global_position_get_lat(msg); - utm_global_position->lon = mavlink_msg_utm_global_position_get_lon(msg); - utm_global_position->alt = mavlink_msg_utm_global_position_get_alt(msg); - utm_global_position->relative_alt = mavlink_msg_utm_global_position_get_relative_alt(msg); - utm_global_position->next_lat = mavlink_msg_utm_global_position_get_next_lat(msg); - utm_global_position->next_lon = mavlink_msg_utm_global_position_get_next_lon(msg); - utm_global_position->next_alt = mavlink_msg_utm_global_position_get_next_alt(msg); - utm_global_position->vx = mavlink_msg_utm_global_position_get_vx(msg); - utm_global_position->vy = mavlink_msg_utm_global_position_get_vy(msg); - utm_global_position->vz = mavlink_msg_utm_global_position_get_vz(msg); - utm_global_position->h_acc = mavlink_msg_utm_global_position_get_h_acc(msg); - utm_global_position->v_acc = mavlink_msg_utm_global_position_get_v_acc(msg); - utm_global_position->vel_acc = mavlink_msg_utm_global_position_get_vel_acc(msg); - utm_global_position->update_rate = mavlink_msg_utm_global_position_get_update_rate(msg); - mavlink_msg_utm_global_position_get_uas_id(msg, utm_global_position->uas_id); - utm_global_position->flight_state = mavlink_msg_utm_global_position_get_flight_state(msg); - utm_global_position->flags = mavlink_msg_utm_global_position_get_flags(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_UTM_GLOBAL_POSITION_LEN? msg->len : MAVLINK_MSG_ID_UTM_GLOBAL_POSITION_LEN; - memset(utm_global_position, 0, MAVLINK_MSG_ID_UTM_GLOBAL_POSITION_LEN); - memcpy(utm_global_position, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_v2_extension.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_v2_extension.h deleted file mode 100644 index 93c652e6..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_v2_extension.h +++ /dev/null @@ -1,305 +0,0 @@ -#pragma once -// MESSAGE V2_EXTENSION PACKING - -#define MAVLINK_MSG_ID_V2_EXTENSION 248 - - -typedef struct __mavlink_v2_extension_t { - uint16_t message_type; /*< A code that identifies the software component that understands this message (analogous to USB device classes or mime type strings). If this code is less than 32768, it is considered a 'registered' protocol extension and the corresponding entry should be added to https://github.com/mavlink/mavlink/definition_files/extension_message_ids.xml. Software creators can register blocks of message IDs as needed (useful for GCS specific metadata, etc...). Message_types greater than 32767 are considered local experiments and should not be checked in to any widely distributed codebase.*/ - uint8_t target_network; /*< Network ID (0 for broadcast)*/ - uint8_t target_system; /*< System ID (0 for broadcast)*/ - uint8_t target_component; /*< Component ID (0 for broadcast)*/ - uint8_t payload[249]; /*< Variable length payload. The length must be encoded in the payload as part of the message_type protocol, e.g. by including the length as payload data, or by terminating the payload data with a non-zero marker. This is required in order to reconstruct zero-terminated payloads that are (or otherwise would be) trimmed by MAVLink 2 empty-byte truncation. The entire content of the payload block is opaque unless you understand the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the MAVLink specification.*/ -} mavlink_v2_extension_t; - -#define MAVLINK_MSG_ID_V2_EXTENSION_LEN 254 -#define MAVLINK_MSG_ID_V2_EXTENSION_MIN_LEN 254 -#define MAVLINK_MSG_ID_248_LEN 254 -#define MAVLINK_MSG_ID_248_MIN_LEN 254 - -#define MAVLINK_MSG_ID_V2_EXTENSION_CRC 8 -#define MAVLINK_MSG_ID_248_CRC 8 - -#define MAVLINK_MSG_V2_EXTENSION_FIELD_PAYLOAD_LEN 249 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_V2_EXTENSION { \ - 248, \ - "V2_EXTENSION", \ - 5, \ - { { "target_network", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_v2_extension_t, target_network) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_v2_extension_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_v2_extension_t, target_component) }, \ - { "message_type", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_v2_extension_t, message_type) }, \ - { "payload", NULL, MAVLINK_TYPE_UINT8_T, 249, 5, offsetof(mavlink_v2_extension_t, payload) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_V2_EXTENSION { \ - "V2_EXTENSION", \ - 5, \ - { { "target_network", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_v2_extension_t, target_network) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_v2_extension_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_v2_extension_t, target_component) }, \ - { "message_type", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_v2_extension_t, message_type) }, \ - { "payload", NULL, MAVLINK_TYPE_UINT8_T, 249, 5, offsetof(mavlink_v2_extension_t, payload) }, \ - } \ -} -#endif - -/** - * @brief Pack a v2_extension message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_network Network ID (0 for broadcast) - * @param target_system System ID (0 for broadcast) - * @param target_component Component ID (0 for broadcast) - * @param message_type A code that identifies the software component that understands this message (analogous to USB device classes or mime type strings). If this code is less than 32768, it is considered a 'registered' protocol extension and the corresponding entry should be added to https://github.com/mavlink/mavlink/definition_files/extension_message_ids.xml. Software creators can register blocks of message IDs as needed (useful for GCS specific metadata, etc...). Message_types greater than 32767 are considered local experiments and should not be checked in to any widely distributed codebase. - * @param payload Variable length payload. The length must be encoded in the payload as part of the message_type protocol, e.g. by including the length as payload data, or by terminating the payload data with a non-zero marker. This is required in order to reconstruct zero-terminated payloads that are (or otherwise would be) trimmed by MAVLink 2 empty-byte truncation. The entire content of the payload block is opaque unless you understand the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the MAVLink specification. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_v2_extension_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_network, uint8_t target_system, uint8_t target_component, uint16_t message_type, const uint8_t *payload) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_V2_EXTENSION_LEN]; - _mav_put_uint16_t(buf, 0, message_type); - _mav_put_uint8_t(buf, 2, target_network); - _mav_put_uint8_t(buf, 3, target_system); - _mav_put_uint8_t(buf, 4, target_component); - _mav_put_uint8_t_array(buf, 5, payload, 249); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_V2_EXTENSION_LEN); -#else - mavlink_v2_extension_t packet; - packet.message_type = message_type; - packet.target_network = target_network; - packet.target_system = target_system; - packet.target_component = target_component; - mav_array_memcpy(packet.payload, payload, sizeof(uint8_t)*249); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_V2_EXTENSION_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_V2_EXTENSION; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_V2_EXTENSION_MIN_LEN, MAVLINK_MSG_ID_V2_EXTENSION_LEN, MAVLINK_MSG_ID_V2_EXTENSION_CRC); -} - -/** - * @brief Pack a v2_extension message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_network Network ID (0 for broadcast) - * @param target_system System ID (0 for broadcast) - * @param target_component Component ID (0 for broadcast) - * @param message_type A code that identifies the software component that understands this message (analogous to USB device classes or mime type strings). If this code is less than 32768, it is considered a 'registered' protocol extension and the corresponding entry should be added to https://github.com/mavlink/mavlink/definition_files/extension_message_ids.xml. Software creators can register blocks of message IDs as needed (useful for GCS specific metadata, etc...). Message_types greater than 32767 are considered local experiments and should not be checked in to any widely distributed codebase. - * @param payload Variable length payload. The length must be encoded in the payload as part of the message_type protocol, e.g. by including the length as payload data, or by terminating the payload data with a non-zero marker. This is required in order to reconstruct zero-terminated payloads that are (or otherwise would be) trimmed by MAVLink 2 empty-byte truncation. The entire content of the payload block is opaque unless you understand the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the MAVLink specification. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_v2_extension_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_network,uint8_t target_system,uint8_t target_component,uint16_t message_type,const uint8_t *payload) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_V2_EXTENSION_LEN]; - _mav_put_uint16_t(buf, 0, message_type); - _mav_put_uint8_t(buf, 2, target_network); - _mav_put_uint8_t(buf, 3, target_system); - _mav_put_uint8_t(buf, 4, target_component); - _mav_put_uint8_t_array(buf, 5, payload, 249); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_V2_EXTENSION_LEN); -#else - mavlink_v2_extension_t packet; - packet.message_type = message_type; - packet.target_network = target_network; - packet.target_system = target_system; - packet.target_component = target_component; - mav_array_memcpy(packet.payload, payload, sizeof(uint8_t)*249); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_V2_EXTENSION_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_V2_EXTENSION; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_V2_EXTENSION_MIN_LEN, MAVLINK_MSG_ID_V2_EXTENSION_LEN, MAVLINK_MSG_ID_V2_EXTENSION_CRC); -} - -/** - * @brief Encode a v2_extension struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param v2_extension C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_v2_extension_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_v2_extension_t* v2_extension) -{ - return mavlink_msg_v2_extension_pack(system_id, component_id, msg, v2_extension->target_network, v2_extension->target_system, v2_extension->target_component, v2_extension->message_type, v2_extension->payload); -} - -/** - * @brief Encode a v2_extension struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param v2_extension C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_v2_extension_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_v2_extension_t* v2_extension) -{ - return mavlink_msg_v2_extension_pack_chan(system_id, component_id, chan, msg, v2_extension->target_network, v2_extension->target_system, v2_extension->target_component, v2_extension->message_type, v2_extension->payload); -} - -/** - * @brief Send a v2_extension message - * @param chan MAVLink channel to send the message - * - * @param target_network Network ID (0 for broadcast) - * @param target_system System ID (0 for broadcast) - * @param target_component Component ID (0 for broadcast) - * @param message_type A code that identifies the software component that understands this message (analogous to USB device classes or mime type strings). If this code is less than 32768, it is considered a 'registered' protocol extension and the corresponding entry should be added to https://github.com/mavlink/mavlink/definition_files/extension_message_ids.xml. Software creators can register blocks of message IDs as needed (useful for GCS specific metadata, etc...). Message_types greater than 32767 are considered local experiments and should not be checked in to any widely distributed codebase. - * @param payload Variable length payload. The length must be encoded in the payload as part of the message_type protocol, e.g. by including the length as payload data, or by terminating the payload data with a non-zero marker. This is required in order to reconstruct zero-terminated payloads that are (or otherwise would be) trimmed by MAVLink 2 empty-byte truncation. The entire content of the payload block is opaque unless you understand the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the MAVLink specification. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_v2_extension_send(mavlink_channel_t chan, uint8_t target_network, uint8_t target_system, uint8_t target_component, uint16_t message_type, const uint8_t *payload) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_V2_EXTENSION_LEN]; - _mav_put_uint16_t(buf, 0, message_type); - _mav_put_uint8_t(buf, 2, target_network); - _mav_put_uint8_t(buf, 3, target_system); - _mav_put_uint8_t(buf, 4, target_component); - _mav_put_uint8_t_array(buf, 5, payload, 249); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_V2_EXTENSION, buf, MAVLINK_MSG_ID_V2_EXTENSION_MIN_LEN, MAVLINK_MSG_ID_V2_EXTENSION_LEN, MAVLINK_MSG_ID_V2_EXTENSION_CRC); -#else - mavlink_v2_extension_t packet; - packet.message_type = message_type; - packet.target_network = target_network; - packet.target_system = target_system; - packet.target_component = target_component; - mav_array_memcpy(packet.payload, payload, sizeof(uint8_t)*249); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_V2_EXTENSION, (const char *)&packet, MAVLINK_MSG_ID_V2_EXTENSION_MIN_LEN, MAVLINK_MSG_ID_V2_EXTENSION_LEN, MAVLINK_MSG_ID_V2_EXTENSION_CRC); -#endif -} - -/** - * @brief Send a v2_extension message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_v2_extension_send_struct(mavlink_channel_t chan, const mavlink_v2_extension_t* v2_extension) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_v2_extension_send(chan, v2_extension->target_network, v2_extension->target_system, v2_extension->target_component, v2_extension->message_type, v2_extension->payload); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_V2_EXTENSION, (const char *)v2_extension, MAVLINK_MSG_ID_V2_EXTENSION_MIN_LEN, MAVLINK_MSG_ID_V2_EXTENSION_LEN, MAVLINK_MSG_ID_V2_EXTENSION_CRC); -#endif -} - -#if MAVLINK_MSG_ID_V2_EXTENSION_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_v2_extension_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_network, uint8_t target_system, uint8_t target_component, uint16_t message_type, const uint8_t *payload) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint16_t(buf, 0, message_type); - _mav_put_uint8_t(buf, 2, target_network); - _mav_put_uint8_t(buf, 3, target_system); - _mav_put_uint8_t(buf, 4, target_component); - _mav_put_uint8_t_array(buf, 5, payload, 249); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_V2_EXTENSION, buf, MAVLINK_MSG_ID_V2_EXTENSION_MIN_LEN, MAVLINK_MSG_ID_V2_EXTENSION_LEN, MAVLINK_MSG_ID_V2_EXTENSION_CRC); -#else - mavlink_v2_extension_t *packet = (mavlink_v2_extension_t *)msgbuf; - packet->message_type = message_type; - packet->target_network = target_network; - packet->target_system = target_system; - packet->target_component = target_component; - mav_array_memcpy(packet->payload, payload, sizeof(uint8_t)*249); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_V2_EXTENSION, (const char *)packet, MAVLINK_MSG_ID_V2_EXTENSION_MIN_LEN, MAVLINK_MSG_ID_V2_EXTENSION_LEN, MAVLINK_MSG_ID_V2_EXTENSION_CRC); -#endif -} -#endif - -#endif - -// MESSAGE V2_EXTENSION UNPACKING - - -/** - * @brief Get field target_network from v2_extension message - * - * @return Network ID (0 for broadcast) - */ -static inline uint8_t mavlink_msg_v2_extension_get_target_network(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 2); -} - -/** - * @brief Get field target_system from v2_extension message - * - * @return System ID (0 for broadcast) - */ -static inline uint8_t mavlink_msg_v2_extension_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 3); -} - -/** - * @brief Get field target_component from v2_extension message - * - * @return Component ID (0 for broadcast) - */ -static inline uint8_t mavlink_msg_v2_extension_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 4); -} - -/** - * @brief Get field message_type from v2_extension message - * - * @return A code that identifies the software component that understands this message (analogous to USB device classes or mime type strings). If this code is less than 32768, it is considered a 'registered' protocol extension and the corresponding entry should be added to https://github.com/mavlink/mavlink/definition_files/extension_message_ids.xml. Software creators can register blocks of message IDs as needed (useful for GCS specific metadata, etc...). Message_types greater than 32767 are considered local experiments and should not be checked in to any widely distributed codebase. - */ -static inline uint16_t mavlink_msg_v2_extension_get_message_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 0); -} - -/** - * @brief Get field payload from v2_extension message - * - * @return Variable length payload. The length must be encoded in the payload as part of the message_type protocol, e.g. by including the length as payload data, or by terminating the payload data with a non-zero marker. This is required in order to reconstruct zero-terminated payloads that are (or otherwise would be) trimmed by MAVLink 2 empty-byte truncation. The entire content of the payload block is opaque unless you understand the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the MAVLink specification. - */ -static inline uint16_t mavlink_msg_v2_extension_get_payload(const mavlink_message_t* msg, uint8_t *payload) -{ - return _MAV_RETURN_uint8_t_array(msg, payload, 249, 5); -} - -/** - * @brief Decode a v2_extension message into a struct - * - * @param msg The message to decode - * @param v2_extension C-struct to decode the message contents into - */ -static inline void mavlink_msg_v2_extension_decode(const mavlink_message_t* msg, mavlink_v2_extension_t* v2_extension) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - v2_extension->message_type = mavlink_msg_v2_extension_get_message_type(msg); - v2_extension->target_network = mavlink_msg_v2_extension_get_target_network(msg); - v2_extension->target_system = mavlink_msg_v2_extension_get_target_system(msg); - v2_extension->target_component = mavlink_msg_v2_extension_get_target_component(msg); - mavlink_msg_v2_extension_get_payload(msg, v2_extension->payload); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_V2_EXTENSION_LEN? msg->len : MAVLINK_MSG_ID_V2_EXTENSION_LEN; - memset(v2_extension, 0, MAVLINK_MSG_ID_V2_EXTENSION_LEN); - memcpy(v2_extension, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_vfr_hud.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_vfr_hud.h deleted file mode 100644 index 517ec8c5..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_vfr_hud.h +++ /dev/null @@ -1,338 +0,0 @@ -#pragma once -// MESSAGE VFR_HUD PACKING - -#define MAVLINK_MSG_ID_VFR_HUD 74 - - -typedef struct __mavlink_vfr_hud_t { - float airspeed; /*< [m/s] Vehicle speed in form appropriate for vehicle type. For standard aircraft this is typically calibrated airspeed (CAS) or indicated airspeed (IAS) - either of which can be used by a pilot to estimate stall speed.*/ - float groundspeed; /*< [m/s] Current ground speed.*/ - float alt; /*< [m] Current altitude (MSL).*/ - float climb; /*< [m/s] Current climb rate.*/ - int16_t heading; /*< [deg] Current heading in compass units (0-360, 0=north).*/ - uint16_t throttle; /*< [%] Current throttle setting (0 to 100).*/ -} mavlink_vfr_hud_t; - -#define MAVLINK_MSG_ID_VFR_HUD_LEN 20 -#define MAVLINK_MSG_ID_VFR_HUD_MIN_LEN 20 -#define MAVLINK_MSG_ID_74_LEN 20 -#define MAVLINK_MSG_ID_74_MIN_LEN 20 - -#define MAVLINK_MSG_ID_VFR_HUD_CRC 20 -#define MAVLINK_MSG_ID_74_CRC 20 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_VFR_HUD { \ - 74, \ - "VFR_HUD", \ - 6, \ - { { "airspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_vfr_hud_t, airspeed) }, \ - { "groundspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_vfr_hud_t, groundspeed) }, \ - { "heading", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_vfr_hud_t, heading) }, \ - { "throttle", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_vfr_hud_t, throttle) }, \ - { "alt", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_vfr_hud_t, alt) }, \ - { "climb", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_vfr_hud_t, climb) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_VFR_HUD { \ - "VFR_HUD", \ - 6, \ - { { "airspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_vfr_hud_t, airspeed) }, \ - { "groundspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_vfr_hud_t, groundspeed) }, \ - { "heading", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_vfr_hud_t, heading) }, \ - { "throttle", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_vfr_hud_t, throttle) }, \ - { "alt", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_vfr_hud_t, alt) }, \ - { "climb", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_vfr_hud_t, climb) }, \ - } \ -} -#endif - -/** - * @brief Pack a vfr_hud message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param airspeed [m/s] Vehicle speed in form appropriate for vehicle type. For standard aircraft this is typically calibrated airspeed (CAS) or indicated airspeed (IAS) - either of which can be used by a pilot to estimate stall speed. - * @param groundspeed [m/s] Current ground speed. - * @param heading [deg] Current heading in compass units (0-360, 0=north). - * @param throttle [%] Current throttle setting (0 to 100). - * @param alt [m] Current altitude (MSL). - * @param climb [m/s] Current climb rate. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_vfr_hud_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - float airspeed, float groundspeed, int16_t heading, uint16_t throttle, float alt, float climb) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_VFR_HUD_LEN]; - _mav_put_float(buf, 0, airspeed); - _mav_put_float(buf, 4, groundspeed); - _mav_put_float(buf, 8, alt); - _mav_put_float(buf, 12, climb); - _mav_put_int16_t(buf, 16, heading); - _mav_put_uint16_t(buf, 18, throttle); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VFR_HUD_LEN); -#else - mavlink_vfr_hud_t packet; - packet.airspeed = airspeed; - packet.groundspeed = groundspeed; - packet.alt = alt; - packet.climb = climb; - packet.heading = heading; - packet.throttle = throttle; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VFR_HUD_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_VFR_HUD; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_VFR_HUD_MIN_LEN, MAVLINK_MSG_ID_VFR_HUD_LEN, MAVLINK_MSG_ID_VFR_HUD_CRC); -} - -/** - * @brief Pack a vfr_hud message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param airspeed [m/s] Vehicle speed in form appropriate for vehicle type. For standard aircraft this is typically calibrated airspeed (CAS) or indicated airspeed (IAS) - either of which can be used by a pilot to estimate stall speed. - * @param groundspeed [m/s] Current ground speed. - * @param heading [deg] Current heading in compass units (0-360, 0=north). - * @param throttle [%] Current throttle setting (0 to 100). - * @param alt [m] Current altitude (MSL). - * @param climb [m/s] Current climb rate. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_vfr_hud_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - float airspeed,float groundspeed,int16_t heading,uint16_t throttle,float alt,float climb) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_VFR_HUD_LEN]; - _mav_put_float(buf, 0, airspeed); - _mav_put_float(buf, 4, groundspeed); - _mav_put_float(buf, 8, alt); - _mav_put_float(buf, 12, climb); - _mav_put_int16_t(buf, 16, heading); - _mav_put_uint16_t(buf, 18, throttle); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VFR_HUD_LEN); -#else - mavlink_vfr_hud_t packet; - packet.airspeed = airspeed; - packet.groundspeed = groundspeed; - packet.alt = alt; - packet.climb = climb; - packet.heading = heading; - packet.throttle = throttle; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VFR_HUD_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_VFR_HUD; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_VFR_HUD_MIN_LEN, MAVLINK_MSG_ID_VFR_HUD_LEN, MAVLINK_MSG_ID_VFR_HUD_CRC); -} - -/** - * @brief Encode a vfr_hud struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param vfr_hud C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_vfr_hud_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_vfr_hud_t* vfr_hud) -{ - return mavlink_msg_vfr_hud_pack(system_id, component_id, msg, vfr_hud->airspeed, vfr_hud->groundspeed, vfr_hud->heading, vfr_hud->throttle, vfr_hud->alt, vfr_hud->climb); -} - -/** - * @brief Encode a vfr_hud struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param vfr_hud C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_vfr_hud_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_vfr_hud_t* vfr_hud) -{ - return mavlink_msg_vfr_hud_pack_chan(system_id, component_id, chan, msg, vfr_hud->airspeed, vfr_hud->groundspeed, vfr_hud->heading, vfr_hud->throttle, vfr_hud->alt, vfr_hud->climb); -} - -/** - * @brief Send a vfr_hud message - * @param chan MAVLink channel to send the message - * - * @param airspeed [m/s] Vehicle speed in form appropriate for vehicle type. For standard aircraft this is typically calibrated airspeed (CAS) or indicated airspeed (IAS) - either of which can be used by a pilot to estimate stall speed. - * @param groundspeed [m/s] Current ground speed. - * @param heading [deg] Current heading in compass units (0-360, 0=north). - * @param throttle [%] Current throttle setting (0 to 100). - * @param alt [m] Current altitude (MSL). - * @param climb [m/s] Current climb rate. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_vfr_hud_send(mavlink_channel_t chan, float airspeed, float groundspeed, int16_t heading, uint16_t throttle, float alt, float climb) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_VFR_HUD_LEN]; - _mav_put_float(buf, 0, airspeed); - _mav_put_float(buf, 4, groundspeed); - _mav_put_float(buf, 8, alt); - _mav_put_float(buf, 12, climb); - _mav_put_int16_t(buf, 16, heading); - _mav_put_uint16_t(buf, 18, throttle); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VFR_HUD, buf, MAVLINK_MSG_ID_VFR_HUD_MIN_LEN, MAVLINK_MSG_ID_VFR_HUD_LEN, MAVLINK_MSG_ID_VFR_HUD_CRC); -#else - mavlink_vfr_hud_t packet; - packet.airspeed = airspeed; - packet.groundspeed = groundspeed; - packet.alt = alt; - packet.climb = climb; - packet.heading = heading; - packet.throttle = throttle; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VFR_HUD, (const char *)&packet, MAVLINK_MSG_ID_VFR_HUD_MIN_LEN, MAVLINK_MSG_ID_VFR_HUD_LEN, MAVLINK_MSG_ID_VFR_HUD_CRC); -#endif -} - -/** - * @brief Send a vfr_hud message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_vfr_hud_send_struct(mavlink_channel_t chan, const mavlink_vfr_hud_t* vfr_hud) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_vfr_hud_send(chan, vfr_hud->airspeed, vfr_hud->groundspeed, vfr_hud->heading, vfr_hud->throttle, vfr_hud->alt, vfr_hud->climb); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VFR_HUD, (const char *)vfr_hud, MAVLINK_MSG_ID_VFR_HUD_MIN_LEN, MAVLINK_MSG_ID_VFR_HUD_LEN, MAVLINK_MSG_ID_VFR_HUD_CRC); -#endif -} - -#if MAVLINK_MSG_ID_VFR_HUD_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_vfr_hud_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, float airspeed, float groundspeed, int16_t heading, uint16_t throttle, float alt, float climb) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_float(buf, 0, airspeed); - _mav_put_float(buf, 4, groundspeed); - _mav_put_float(buf, 8, alt); - _mav_put_float(buf, 12, climb); - _mav_put_int16_t(buf, 16, heading); - _mav_put_uint16_t(buf, 18, throttle); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VFR_HUD, buf, MAVLINK_MSG_ID_VFR_HUD_MIN_LEN, MAVLINK_MSG_ID_VFR_HUD_LEN, MAVLINK_MSG_ID_VFR_HUD_CRC); -#else - mavlink_vfr_hud_t *packet = (mavlink_vfr_hud_t *)msgbuf; - packet->airspeed = airspeed; - packet->groundspeed = groundspeed; - packet->alt = alt; - packet->climb = climb; - packet->heading = heading; - packet->throttle = throttle; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VFR_HUD, (const char *)packet, MAVLINK_MSG_ID_VFR_HUD_MIN_LEN, MAVLINK_MSG_ID_VFR_HUD_LEN, MAVLINK_MSG_ID_VFR_HUD_CRC); -#endif -} -#endif - -#endif - -// MESSAGE VFR_HUD UNPACKING - - -/** - * @brief Get field airspeed from vfr_hud message - * - * @return [m/s] Vehicle speed in form appropriate for vehicle type. For standard aircraft this is typically calibrated airspeed (CAS) or indicated airspeed (IAS) - either of which can be used by a pilot to estimate stall speed. - */ -static inline float mavlink_msg_vfr_hud_get_airspeed(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 0); -} - -/** - * @brief Get field groundspeed from vfr_hud message - * - * @return [m/s] Current ground speed. - */ -static inline float mavlink_msg_vfr_hud_get_groundspeed(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 4); -} - -/** - * @brief Get field heading from vfr_hud message - * - * @return [deg] Current heading in compass units (0-360, 0=north). - */ -static inline int16_t mavlink_msg_vfr_hud_get_heading(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 16); -} - -/** - * @brief Get field throttle from vfr_hud message - * - * @return [%] Current throttle setting (0 to 100). - */ -static inline uint16_t mavlink_msg_vfr_hud_get_throttle(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 18); -} - -/** - * @brief Get field alt from vfr_hud message - * - * @return [m] Current altitude (MSL). - */ -static inline float mavlink_msg_vfr_hud_get_alt(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field climb from vfr_hud message - * - * @return [m/s] Current climb rate. - */ -static inline float mavlink_msg_vfr_hud_get_climb(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Decode a vfr_hud message into a struct - * - * @param msg The message to decode - * @param vfr_hud C-struct to decode the message contents into - */ -static inline void mavlink_msg_vfr_hud_decode(const mavlink_message_t* msg, mavlink_vfr_hud_t* vfr_hud) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - vfr_hud->airspeed = mavlink_msg_vfr_hud_get_airspeed(msg); - vfr_hud->groundspeed = mavlink_msg_vfr_hud_get_groundspeed(msg); - vfr_hud->alt = mavlink_msg_vfr_hud_get_alt(msg); - vfr_hud->climb = mavlink_msg_vfr_hud_get_climb(msg); - vfr_hud->heading = mavlink_msg_vfr_hud_get_heading(msg); - vfr_hud->throttle = mavlink_msg_vfr_hud_get_throttle(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_VFR_HUD_LEN? msg->len : MAVLINK_MSG_ID_VFR_HUD_LEN; - memset(vfr_hud, 0, MAVLINK_MSG_ID_VFR_HUD_LEN); - memcpy(vfr_hud, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_vibration.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_vibration.h deleted file mode 100644 index 1d029260..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_vibration.h +++ /dev/null @@ -1,363 +0,0 @@ -#pragma once -// MESSAGE VIBRATION PACKING - -#define MAVLINK_MSG_ID_VIBRATION 241 - - -typedef struct __mavlink_vibration_t { - uint64_t time_usec; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/ - float vibration_x; /*< Vibration levels on X-axis*/ - float vibration_y; /*< Vibration levels on Y-axis*/ - float vibration_z; /*< Vibration levels on Z-axis*/ - uint32_t clipping_0; /*< first accelerometer clipping count*/ - uint32_t clipping_1; /*< second accelerometer clipping count*/ - uint32_t clipping_2; /*< third accelerometer clipping count*/ -} mavlink_vibration_t; - -#define MAVLINK_MSG_ID_VIBRATION_LEN 32 -#define MAVLINK_MSG_ID_VIBRATION_MIN_LEN 32 -#define MAVLINK_MSG_ID_241_LEN 32 -#define MAVLINK_MSG_ID_241_MIN_LEN 32 - -#define MAVLINK_MSG_ID_VIBRATION_CRC 90 -#define MAVLINK_MSG_ID_241_CRC 90 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_VIBRATION { \ - 241, \ - "VIBRATION", \ - 7, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_vibration_t, time_usec) }, \ - { "vibration_x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_vibration_t, vibration_x) }, \ - { "vibration_y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_vibration_t, vibration_y) }, \ - { "vibration_z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_vibration_t, vibration_z) }, \ - { "clipping_0", NULL, MAVLINK_TYPE_UINT32_T, 0, 20, offsetof(mavlink_vibration_t, clipping_0) }, \ - { "clipping_1", NULL, MAVLINK_TYPE_UINT32_T, 0, 24, offsetof(mavlink_vibration_t, clipping_1) }, \ - { "clipping_2", NULL, MAVLINK_TYPE_UINT32_T, 0, 28, offsetof(mavlink_vibration_t, clipping_2) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_VIBRATION { \ - "VIBRATION", \ - 7, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_vibration_t, time_usec) }, \ - { "vibration_x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_vibration_t, vibration_x) }, \ - { "vibration_y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_vibration_t, vibration_y) }, \ - { "vibration_z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_vibration_t, vibration_z) }, \ - { "clipping_0", NULL, MAVLINK_TYPE_UINT32_T, 0, 20, offsetof(mavlink_vibration_t, clipping_0) }, \ - { "clipping_1", NULL, MAVLINK_TYPE_UINT32_T, 0, 24, offsetof(mavlink_vibration_t, clipping_1) }, \ - { "clipping_2", NULL, MAVLINK_TYPE_UINT32_T, 0, 28, offsetof(mavlink_vibration_t, clipping_2) }, \ - } \ -} -#endif - -/** - * @brief Pack a vibration message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @param vibration_x Vibration levels on X-axis - * @param vibration_y Vibration levels on Y-axis - * @param vibration_z Vibration levels on Z-axis - * @param clipping_0 first accelerometer clipping count - * @param clipping_1 second accelerometer clipping count - * @param clipping_2 third accelerometer clipping count - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_vibration_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint64_t time_usec, float vibration_x, float vibration_y, float vibration_z, uint32_t clipping_0, uint32_t clipping_1, uint32_t clipping_2) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_VIBRATION_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, vibration_x); - _mav_put_float(buf, 12, vibration_y); - _mav_put_float(buf, 16, vibration_z); - _mav_put_uint32_t(buf, 20, clipping_0); - _mav_put_uint32_t(buf, 24, clipping_1); - _mav_put_uint32_t(buf, 28, clipping_2); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VIBRATION_LEN); -#else - mavlink_vibration_t packet; - packet.time_usec = time_usec; - packet.vibration_x = vibration_x; - packet.vibration_y = vibration_y; - packet.vibration_z = vibration_z; - packet.clipping_0 = clipping_0; - packet.clipping_1 = clipping_1; - packet.clipping_2 = clipping_2; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VIBRATION_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_VIBRATION; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_VIBRATION_MIN_LEN, MAVLINK_MSG_ID_VIBRATION_LEN, MAVLINK_MSG_ID_VIBRATION_CRC); -} - -/** - * @brief Pack a vibration message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @param vibration_x Vibration levels on X-axis - * @param vibration_y Vibration levels on Y-axis - * @param vibration_z Vibration levels on Z-axis - * @param clipping_0 first accelerometer clipping count - * @param clipping_1 second accelerometer clipping count - * @param clipping_2 third accelerometer clipping count - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_vibration_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint64_t time_usec,float vibration_x,float vibration_y,float vibration_z,uint32_t clipping_0,uint32_t clipping_1,uint32_t clipping_2) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_VIBRATION_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, vibration_x); - _mav_put_float(buf, 12, vibration_y); - _mav_put_float(buf, 16, vibration_z); - _mav_put_uint32_t(buf, 20, clipping_0); - _mav_put_uint32_t(buf, 24, clipping_1); - _mav_put_uint32_t(buf, 28, clipping_2); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VIBRATION_LEN); -#else - mavlink_vibration_t packet; - packet.time_usec = time_usec; - packet.vibration_x = vibration_x; - packet.vibration_y = vibration_y; - packet.vibration_z = vibration_z; - packet.clipping_0 = clipping_0; - packet.clipping_1 = clipping_1; - packet.clipping_2 = clipping_2; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VIBRATION_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_VIBRATION; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_VIBRATION_MIN_LEN, MAVLINK_MSG_ID_VIBRATION_LEN, MAVLINK_MSG_ID_VIBRATION_CRC); -} - -/** - * @brief Encode a vibration struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param vibration C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_vibration_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_vibration_t* vibration) -{ - return mavlink_msg_vibration_pack(system_id, component_id, msg, vibration->time_usec, vibration->vibration_x, vibration->vibration_y, vibration->vibration_z, vibration->clipping_0, vibration->clipping_1, vibration->clipping_2); -} - -/** - * @brief Encode a vibration struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param vibration C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_vibration_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_vibration_t* vibration) -{ - return mavlink_msg_vibration_pack_chan(system_id, component_id, chan, msg, vibration->time_usec, vibration->vibration_x, vibration->vibration_y, vibration->vibration_z, vibration->clipping_0, vibration->clipping_1, vibration->clipping_2); -} - -/** - * @brief Send a vibration message - * @param chan MAVLink channel to send the message - * - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @param vibration_x Vibration levels on X-axis - * @param vibration_y Vibration levels on Y-axis - * @param vibration_z Vibration levels on Z-axis - * @param clipping_0 first accelerometer clipping count - * @param clipping_1 second accelerometer clipping count - * @param clipping_2 third accelerometer clipping count - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_vibration_send(mavlink_channel_t chan, uint64_t time_usec, float vibration_x, float vibration_y, float vibration_z, uint32_t clipping_0, uint32_t clipping_1, uint32_t clipping_2) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_VIBRATION_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, vibration_x); - _mav_put_float(buf, 12, vibration_y); - _mav_put_float(buf, 16, vibration_z); - _mav_put_uint32_t(buf, 20, clipping_0); - _mav_put_uint32_t(buf, 24, clipping_1); - _mav_put_uint32_t(buf, 28, clipping_2); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VIBRATION, buf, MAVLINK_MSG_ID_VIBRATION_MIN_LEN, MAVLINK_MSG_ID_VIBRATION_LEN, MAVLINK_MSG_ID_VIBRATION_CRC); -#else - mavlink_vibration_t packet; - packet.time_usec = time_usec; - packet.vibration_x = vibration_x; - packet.vibration_y = vibration_y; - packet.vibration_z = vibration_z; - packet.clipping_0 = clipping_0; - packet.clipping_1 = clipping_1; - packet.clipping_2 = clipping_2; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VIBRATION, (const char *)&packet, MAVLINK_MSG_ID_VIBRATION_MIN_LEN, MAVLINK_MSG_ID_VIBRATION_LEN, MAVLINK_MSG_ID_VIBRATION_CRC); -#endif -} - -/** - * @brief Send a vibration message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_vibration_send_struct(mavlink_channel_t chan, const mavlink_vibration_t* vibration) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_vibration_send(chan, vibration->time_usec, vibration->vibration_x, vibration->vibration_y, vibration->vibration_z, vibration->clipping_0, vibration->clipping_1, vibration->clipping_2); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VIBRATION, (const char *)vibration, MAVLINK_MSG_ID_VIBRATION_MIN_LEN, MAVLINK_MSG_ID_VIBRATION_LEN, MAVLINK_MSG_ID_VIBRATION_CRC); -#endif -} - -#if MAVLINK_MSG_ID_VIBRATION_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_vibration_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, float vibration_x, float vibration_y, float vibration_z, uint32_t clipping_0, uint32_t clipping_1, uint32_t clipping_2) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, vibration_x); - _mav_put_float(buf, 12, vibration_y); - _mav_put_float(buf, 16, vibration_z); - _mav_put_uint32_t(buf, 20, clipping_0); - _mav_put_uint32_t(buf, 24, clipping_1); - _mav_put_uint32_t(buf, 28, clipping_2); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VIBRATION, buf, MAVLINK_MSG_ID_VIBRATION_MIN_LEN, MAVLINK_MSG_ID_VIBRATION_LEN, MAVLINK_MSG_ID_VIBRATION_CRC); -#else - mavlink_vibration_t *packet = (mavlink_vibration_t *)msgbuf; - packet->time_usec = time_usec; - packet->vibration_x = vibration_x; - packet->vibration_y = vibration_y; - packet->vibration_z = vibration_z; - packet->clipping_0 = clipping_0; - packet->clipping_1 = clipping_1; - packet->clipping_2 = clipping_2; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VIBRATION, (const char *)packet, MAVLINK_MSG_ID_VIBRATION_MIN_LEN, MAVLINK_MSG_ID_VIBRATION_LEN, MAVLINK_MSG_ID_VIBRATION_CRC); -#endif -} -#endif - -#endif - -// MESSAGE VIBRATION UNPACKING - - -/** - * @brief Get field time_usec from vibration message - * - * @return [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - */ -static inline uint64_t mavlink_msg_vibration_get_time_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field vibration_x from vibration message - * - * @return Vibration levels on X-axis - */ -static inline float mavlink_msg_vibration_get_vibration_x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field vibration_y from vibration message - * - * @return Vibration levels on Y-axis - */ -static inline float mavlink_msg_vibration_get_vibration_y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field vibration_z from vibration message - * - * @return Vibration levels on Z-axis - */ -static inline float mavlink_msg_vibration_get_vibration_z(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field clipping_0 from vibration message - * - * @return first accelerometer clipping count - */ -static inline uint32_t mavlink_msg_vibration_get_clipping_0(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 20); -} - -/** - * @brief Get field clipping_1 from vibration message - * - * @return second accelerometer clipping count - */ -static inline uint32_t mavlink_msg_vibration_get_clipping_1(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 24); -} - -/** - * @brief Get field clipping_2 from vibration message - * - * @return third accelerometer clipping count - */ -static inline uint32_t mavlink_msg_vibration_get_clipping_2(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 28); -} - -/** - * @brief Decode a vibration message into a struct - * - * @param msg The message to decode - * @param vibration C-struct to decode the message contents into - */ -static inline void mavlink_msg_vibration_decode(const mavlink_message_t* msg, mavlink_vibration_t* vibration) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - vibration->time_usec = mavlink_msg_vibration_get_time_usec(msg); - vibration->vibration_x = mavlink_msg_vibration_get_vibration_x(msg); - vibration->vibration_y = mavlink_msg_vibration_get_vibration_y(msg); - vibration->vibration_z = mavlink_msg_vibration_get_vibration_z(msg); - vibration->clipping_0 = mavlink_msg_vibration_get_clipping_0(msg); - vibration->clipping_1 = mavlink_msg_vibration_get_clipping_1(msg); - vibration->clipping_2 = mavlink_msg_vibration_get_clipping_2(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_VIBRATION_LEN? msg->len : MAVLINK_MSG_ID_VIBRATION_LEN; - memset(vibration, 0, MAVLINK_MSG_ID_VIBRATION_LEN); - memcpy(vibration, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_vicon_position_estimate.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_vicon_position_estimate.h deleted file mode 100644 index 8dc89fcf..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_vicon_position_estimate.h +++ /dev/null @@ -1,380 +0,0 @@ -#pragma once -// MESSAGE VICON_POSITION_ESTIMATE PACKING - -#define MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE 104 - - -typedef struct __mavlink_vicon_position_estimate_t { - uint64_t usec; /*< [us] Timestamp (UNIX time or time since system boot)*/ - float x; /*< [m] Global X position*/ - float y; /*< [m] Global Y position*/ - float z; /*< [m] Global Z position*/ - float roll; /*< [rad] Roll angle*/ - float pitch; /*< [rad] Pitch angle*/ - float yaw; /*< [rad] Yaw angle*/ - float covariance[21]; /*< Row-major representation of 6x6 pose cross-covariance matrix upper right triangle (states: x, y, z, roll, pitch, yaw; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array.*/ -} mavlink_vicon_position_estimate_t; - -#define MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN 116 -#define MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_MIN_LEN 32 -#define MAVLINK_MSG_ID_104_LEN 116 -#define MAVLINK_MSG_ID_104_MIN_LEN 32 - -#define MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_CRC 56 -#define MAVLINK_MSG_ID_104_CRC 56 - -#define MAVLINK_MSG_VICON_POSITION_ESTIMATE_FIELD_COVARIANCE_LEN 21 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_VICON_POSITION_ESTIMATE { \ - 104, \ - "VICON_POSITION_ESTIMATE", \ - 8, \ - { { "usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_vicon_position_estimate_t, usec) }, \ - { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_vicon_position_estimate_t, x) }, \ - { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_vicon_position_estimate_t, y) }, \ - { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_vicon_position_estimate_t, z) }, \ - { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_vicon_position_estimate_t, roll) }, \ - { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_vicon_position_estimate_t, pitch) }, \ - { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_vicon_position_estimate_t, yaw) }, \ - { "covariance", NULL, MAVLINK_TYPE_FLOAT, 21, 32, offsetof(mavlink_vicon_position_estimate_t, covariance) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_VICON_POSITION_ESTIMATE { \ - "VICON_POSITION_ESTIMATE", \ - 8, \ - { { "usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_vicon_position_estimate_t, usec) }, \ - { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_vicon_position_estimate_t, x) }, \ - { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_vicon_position_estimate_t, y) }, \ - { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_vicon_position_estimate_t, z) }, \ - { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_vicon_position_estimate_t, roll) }, \ - { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_vicon_position_estimate_t, pitch) }, \ - { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_vicon_position_estimate_t, yaw) }, \ - { "covariance", NULL, MAVLINK_TYPE_FLOAT, 21, 32, offsetof(mavlink_vicon_position_estimate_t, covariance) }, \ - } \ -} -#endif - -/** - * @brief Pack a vicon_position_estimate message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param usec [us] Timestamp (UNIX time or time since system boot) - * @param x [m] Global X position - * @param y [m] Global Y position - * @param z [m] Global Z position - * @param roll [rad] Roll angle - * @param pitch [rad] Pitch angle - * @param yaw [rad] Yaw angle - * @param covariance Row-major representation of 6x6 pose cross-covariance matrix upper right triangle (states: x, y, z, roll, pitch, yaw; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_vicon_position_estimate_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint64_t usec, float x, float y, float z, float roll, float pitch, float yaw, const float *covariance) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN]; - _mav_put_uint64_t(buf, 0, usec); - _mav_put_float(buf, 8, x); - _mav_put_float(buf, 12, y); - _mav_put_float(buf, 16, z); - _mav_put_float(buf, 20, roll); - _mav_put_float(buf, 24, pitch); - _mav_put_float(buf, 28, yaw); - _mav_put_float_array(buf, 32, covariance, 21); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN); -#else - mavlink_vicon_position_estimate_t packet; - packet.usec = usec; - packet.x = x; - packet.y = y; - packet.z = z; - packet.roll = roll; - packet.pitch = pitch; - packet.yaw = yaw; - mav_array_memcpy(packet.covariance, covariance, sizeof(float)*21); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_MIN_LEN, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_CRC); -} - -/** - * @brief Pack a vicon_position_estimate message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param usec [us] Timestamp (UNIX time or time since system boot) - * @param x [m] Global X position - * @param y [m] Global Y position - * @param z [m] Global Z position - * @param roll [rad] Roll angle - * @param pitch [rad] Pitch angle - * @param yaw [rad] Yaw angle - * @param covariance Row-major representation of 6x6 pose cross-covariance matrix upper right triangle (states: x, y, z, roll, pitch, yaw; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_vicon_position_estimate_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint64_t usec,float x,float y,float z,float roll,float pitch,float yaw,const float *covariance) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN]; - _mav_put_uint64_t(buf, 0, usec); - _mav_put_float(buf, 8, x); - _mav_put_float(buf, 12, y); - _mav_put_float(buf, 16, z); - _mav_put_float(buf, 20, roll); - _mav_put_float(buf, 24, pitch); - _mav_put_float(buf, 28, yaw); - _mav_put_float_array(buf, 32, covariance, 21); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN); -#else - mavlink_vicon_position_estimate_t packet; - packet.usec = usec; - packet.x = x; - packet.y = y; - packet.z = z; - packet.roll = roll; - packet.pitch = pitch; - packet.yaw = yaw; - mav_array_memcpy(packet.covariance, covariance, sizeof(float)*21); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_MIN_LEN, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_CRC); -} - -/** - * @brief Encode a vicon_position_estimate struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param vicon_position_estimate C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_vicon_position_estimate_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_vicon_position_estimate_t* vicon_position_estimate) -{ - return mavlink_msg_vicon_position_estimate_pack(system_id, component_id, msg, vicon_position_estimate->usec, vicon_position_estimate->x, vicon_position_estimate->y, vicon_position_estimate->z, vicon_position_estimate->roll, vicon_position_estimate->pitch, vicon_position_estimate->yaw, vicon_position_estimate->covariance); -} - -/** - * @brief Encode a vicon_position_estimate struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param vicon_position_estimate C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_vicon_position_estimate_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_vicon_position_estimate_t* vicon_position_estimate) -{ - return mavlink_msg_vicon_position_estimate_pack_chan(system_id, component_id, chan, msg, vicon_position_estimate->usec, vicon_position_estimate->x, vicon_position_estimate->y, vicon_position_estimate->z, vicon_position_estimate->roll, vicon_position_estimate->pitch, vicon_position_estimate->yaw, vicon_position_estimate->covariance); -} - -/** - * @brief Send a vicon_position_estimate message - * @param chan MAVLink channel to send the message - * - * @param usec [us] Timestamp (UNIX time or time since system boot) - * @param x [m] Global X position - * @param y [m] Global Y position - * @param z [m] Global Z position - * @param roll [rad] Roll angle - * @param pitch [rad] Pitch angle - * @param yaw [rad] Yaw angle - * @param covariance Row-major representation of 6x6 pose cross-covariance matrix upper right triangle (states: x, y, z, roll, pitch, yaw; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_vicon_position_estimate_send(mavlink_channel_t chan, uint64_t usec, float x, float y, float z, float roll, float pitch, float yaw, const float *covariance) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN]; - _mav_put_uint64_t(buf, 0, usec); - _mav_put_float(buf, 8, x); - _mav_put_float(buf, 12, y); - _mav_put_float(buf, 16, z); - _mav_put_float(buf, 20, roll); - _mav_put_float(buf, 24, pitch); - _mav_put_float(buf, 28, yaw); - _mav_put_float_array(buf, 32, covariance, 21); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE, buf, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_MIN_LEN, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_CRC); -#else - mavlink_vicon_position_estimate_t packet; - packet.usec = usec; - packet.x = x; - packet.y = y; - packet.z = z; - packet.roll = roll; - packet.pitch = pitch; - packet.yaw = yaw; - mav_array_memcpy(packet.covariance, covariance, sizeof(float)*21); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE, (const char *)&packet, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_MIN_LEN, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_CRC); -#endif -} - -/** - * @brief Send a vicon_position_estimate message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_vicon_position_estimate_send_struct(mavlink_channel_t chan, const mavlink_vicon_position_estimate_t* vicon_position_estimate) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_vicon_position_estimate_send(chan, vicon_position_estimate->usec, vicon_position_estimate->x, vicon_position_estimate->y, vicon_position_estimate->z, vicon_position_estimate->roll, vicon_position_estimate->pitch, vicon_position_estimate->yaw, vicon_position_estimate->covariance); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE, (const char *)vicon_position_estimate, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_MIN_LEN, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_CRC); -#endif -} - -#if MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_vicon_position_estimate_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t usec, float x, float y, float z, float roll, float pitch, float yaw, const float *covariance) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, usec); - _mav_put_float(buf, 8, x); - _mav_put_float(buf, 12, y); - _mav_put_float(buf, 16, z); - _mav_put_float(buf, 20, roll); - _mav_put_float(buf, 24, pitch); - _mav_put_float(buf, 28, yaw); - _mav_put_float_array(buf, 32, covariance, 21); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE, buf, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_MIN_LEN, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_CRC); -#else - mavlink_vicon_position_estimate_t *packet = (mavlink_vicon_position_estimate_t *)msgbuf; - packet->usec = usec; - packet->x = x; - packet->y = y; - packet->z = z; - packet->roll = roll; - packet->pitch = pitch; - packet->yaw = yaw; - mav_array_memcpy(packet->covariance, covariance, sizeof(float)*21); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE, (const char *)packet, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_MIN_LEN, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_CRC); -#endif -} -#endif - -#endif - -// MESSAGE VICON_POSITION_ESTIMATE UNPACKING - - -/** - * @brief Get field usec from vicon_position_estimate message - * - * @return [us] Timestamp (UNIX time or time since system boot) - */ -static inline uint64_t mavlink_msg_vicon_position_estimate_get_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field x from vicon_position_estimate message - * - * @return [m] Global X position - */ -static inline float mavlink_msg_vicon_position_estimate_get_x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field y from vicon_position_estimate message - * - * @return [m] Global Y position - */ -static inline float mavlink_msg_vicon_position_estimate_get_y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field z from vicon_position_estimate message - * - * @return [m] Global Z position - */ -static inline float mavlink_msg_vicon_position_estimate_get_z(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field roll from vicon_position_estimate message - * - * @return [rad] Roll angle - */ -static inline float mavlink_msg_vicon_position_estimate_get_roll(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Get field pitch from vicon_position_estimate message - * - * @return [rad] Pitch angle - */ -static inline float mavlink_msg_vicon_position_estimate_get_pitch(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Get field yaw from vicon_position_estimate message - * - * @return [rad] Yaw angle - */ -static inline float mavlink_msg_vicon_position_estimate_get_yaw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 28); -} - -/** - * @brief Get field covariance from vicon_position_estimate message - * - * @return Row-major representation of 6x6 pose cross-covariance matrix upper right triangle (states: x, y, z, roll, pitch, yaw; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array. - */ -static inline uint16_t mavlink_msg_vicon_position_estimate_get_covariance(const mavlink_message_t* msg, float *covariance) -{ - return _MAV_RETURN_float_array(msg, covariance, 21, 32); -} - -/** - * @brief Decode a vicon_position_estimate message into a struct - * - * @param msg The message to decode - * @param vicon_position_estimate C-struct to decode the message contents into - */ -static inline void mavlink_msg_vicon_position_estimate_decode(const mavlink_message_t* msg, mavlink_vicon_position_estimate_t* vicon_position_estimate) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - vicon_position_estimate->usec = mavlink_msg_vicon_position_estimate_get_usec(msg); - vicon_position_estimate->x = mavlink_msg_vicon_position_estimate_get_x(msg); - vicon_position_estimate->y = mavlink_msg_vicon_position_estimate_get_y(msg); - vicon_position_estimate->z = mavlink_msg_vicon_position_estimate_get_z(msg); - vicon_position_estimate->roll = mavlink_msg_vicon_position_estimate_get_roll(msg); - vicon_position_estimate->pitch = mavlink_msg_vicon_position_estimate_get_pitch(msg); - vicon_position_estimate->yaw = mavlink_msg_vicon_position_estimate_get_yaw(msg); - mavlink_msg_vicon_position_estimate_get_covariance(msg, vicon_position_estimate->covariance); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN? msg->len : MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN; - memset(vicon_position_estimate, 0, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN); - memcpy(vicon_position_estimate, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_video_stream_information.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_video_stream_information.h deleted file mode 100644 index 2e9ea7f4..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_video_stream_information.h +++ /dev/null @@ -1,481 +0,0 @@ -#pragma once -// MESSAGE VIDEO_STREAM_INFORMATION PACKING - -#define MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION 269 - - -typedef struct __mavlink_video_stream_information_t { - float framerate; /*< [Hz] Frame rate.*/ - uint32_t bitrate; /*< [bits/s] Bit rate.*/ - uint16_t flags; /*< Bitmap of stream status flags.*/ - uint16_t resolution_h; /*< [pix] Horizontal resolution.*/ - uint16_t resolution_v; /*< [pix] Vertical resolution.*/ - uint16_t rotation; /*< [deg] Video image rotation clockwise.*/ - uint16_t hfov; /*< [deg] Horizontal Field of view.*/ - uint8_t stream_id; /*< Video Stream ID (1 for first, 2 for second, etc.)*/ - uint8_t count; /*< Number of streams available.*/ - uint8_t type; /*< Type of stream.*/ - char name[32]; /*< Stream name.*/ - char uri[160]; /*< Video stream URI (TCP or RTSP URI ground station should connect to) or port number (UDP port ground station should listen to).*/ -} mavlink_video_stream_information_t; - -#define MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION_LEN 213 -#define MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION_MIN_LEN 213 -#define MAVLINK_MSG_ID_269_LEN 213 -#define MAVLINK_MSG_ID_269_MIN_LEN 213 - -#define MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION_CRC 109 -#define MAVLINK_MSG_ID_269_CRC 109 - -#define MAVLINK_MSG_VIDEO_STREAM_INFORMATION_FIELD_NAME_LEN 32 -#define MAVLINK_MSG_VIDEO_STREAM_INFORMATION_FIELD_URI_LEN 160 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_VIDEO_STREAM_INFORMATION { \ - 269, \ - "VIDEO_STREAM_INFORMATION", \ - 12, \ - { { "stream_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 18, offsetof(mavlink_video_stream_information_t, stream_id) }, \ - { "count", NULL, MAVLINK_TYPE_UINT8_T, 0, 19, offsetof(mavlink_video_stream_information_t, count) }, \ - { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_video_stream_information_t, type) }, \ - { "flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_video_stream_information_t, flags) }, \ - { "framerate", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_video_stream_information_t, framerate) }, \ - { "resolution_h", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_video_stream_information_t, resolution_h) }, \ - { "resolution_v", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_video_stream_information_t, resolution_v) }, \ - { "bitrate", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_video_stream_information_t, bitrate) }, \ - { "rotation", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_video_stream_information_t, rotation) }, \ - { "hfov", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_video_stream_information_t, hfov) }, \ - { "name", NULL, MAVLINK_TYPE_CHAR, 32, 21, offsetof(mavlink_video_stream_information_t, name) }, \ - { "uri", NULL, MAVLINK_TYPE_CHAR, 160, 53, offsetof(mavlink_video_stream_information_t, uri) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_VIDEO_STREAM_INFORMATION { \ - "VIDEO_STREAM_INFORMATION", \ - 12, \ - { { "stream_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 18, offsetof(mavlink_video_stream_information_t, stream_id) }, \ - { "count", NULL, MAVLINK_TYPE_UINT8_T, 0, 19, offsetof(mavlink_video_stream_information_t, count) }, \ - { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_video_stream_information_t, type) }, \ - { "flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_video_stream_information_t, flags) }, \ - { "framerate", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_video_stream_information_t, framerate) }, \ - { "resolution_h", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_video_stream_information_t, resolution_h) }, \ - { "resolution_v", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_video_stream_information_t, resolution_v) }, \ - { "bitrate", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_video_stream_information_t, bitrate) }, \ - { "rotation", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_video_stream_information_t, rotation) }, \ - { "hfov", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_video_stream_information_t, hfov) }, \ - { "name", NULL, MAVLINK_TYPE_CHAR, 32, 21, offsetof(mavlink_video_stream_information_t, name) }, \ - { "uri", NULL, MAVLINK_TYPE_CHAR, 160, 53, offsetof(mavlink_video_stream_information_t, uri) }, \ - } \ -} -#endif - -/** - * @brief Pack a video_stream_information message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param stream_id Video Stream ID (1 for first, 2 for second, etc.) - * @param count Number of streams available. - * @param type Type of stream. - * @param flags Bitmap of stream status flags. - * @param framerate [Hz] Frame rate. - * @param resolution_h [pix] Horizontal resolution. - * @param resolution_v [pix] Vertical resolution. - * @param bitrate [bits/s] Bit rate. - * @param rotation [deg] Video image rotation clockwise. - * @param hfov [deg] Horizontal Field of view. - * @param name Stream name. - * @param uri Video stream URI (TCP or RTSP URI ground station should connect to) or port number (UDP port ground station should listen to). - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_video_stream_information_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t stream_id, uint8_t count, uint8_t type, uint16_t flags, float framerate, uint16_t resolution_h, uint16_t resolution_v, uint32_t bitrate, uint16_t rotation, uint16_t hfov, const char *name, const char *uri) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION_LEN]; - _mav_put_float(buf, 0, framerate); - _mav_put_uint32_t(buf, 4, bitrate); - _mav_put_uint16_t(buf, 8, flags); - _mav_put_uint16_t(buf, 10, resolution_h); - _mav_put_uint16_t(buf, 12, resolution_v); - _mav_put_uint16_t(buf, 14, rotation); - _mav_put_uint16_t(buf, 16, hfov); - _mav_put_uint8_t(buf, 18, stream_id); - _mav_put_uint8_t(buf, 19, count); - _mav_put_uint8_t(buf, 20, type); - _mav_put_char_array(buf, 21, name, 32); - _mav_put_char_array(buf, 53, uri, 160); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION_LEN); -#else - mavlink_video_stream_information_t packet; - packet.framerate = framerate; - packet.bitrate = bitrate; - packet.flags = flags; - packet.resolution_h = resolution_h; - packet.resolution_v = resolution_v; - packet.rotation = rotation; - packet.hfov = hfov; - packet.stream_id = stream_id; - packet.count = count; - packet.type = type; - mav_array_memcpy(packet.name, name, sizeof(char)*32); - mav_array_memcpy(packet.uri, uri, sizeof(char)*160); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION_LEN, MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION_CRC); -} - -/** - * @brief Pack a video_stream_information message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param stream_id Video Stream ID (1 for first, 2 for second, etc.) - * @param count Number of streams available. - * @param type Type of stream. - * @param flags Bitmap of stream status flags. - * @param framerate [Hz] Frame rate. - * @param resolution_h [pix] Horizontal resolution. - * @param resolution_v [pix] Vertical resolution. - * @param bitrate [bits/s] Bit rate. - * @param rotation [deg] Video image rotation clockwise. - * @param hfov [deg] Horizontal Field of view. - * @param name Stream name. - * @param uri Video stream URI (TCP or RTSP URI ground station should connect to) or port number (UDP port ground station should listen to). - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_video_stream_information_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t stream_id,uint8_t count,uint8_t type,uint16_t flags,float framerate,uint16_t resolution_h,uint16_t resolution_v,uint32_t bitrate,uint16_t rotation,uint16_t hfov,const char *name,const char *uri) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION_LEN]; - _mav_put_float(buf, 0, framerate); - _mav_put_uint32_t(buf, 4, bitrate); - _mav_put_uint16_t(buf, 8, flags); - _mav_put_uint16_t(buf, 10, resolution_h); - _mav_put_uint16_t(buf, 12, resolution_v); - _mav_put_uint16_t(buf, 14, rotation); - _mav_put_uint16_t(buf, 16, hfov); - _mav_put_uint8_t(buf, 18, stream_id); - _mav_put_uint8_t(buf, 19, count); - _mav_put_uint8_t(buf, 20, type); - _mav_put_char_array(buf, 21, name, 32); - _mav_put_char_array(buf, 53, uri, 160); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION_LEN); -#else - mavlink_video_stream_information_t packet; - packet.framerate = framerate; - packet.bitrate = bitrate; - packet.flags = flags; - packet.resolution_h = resolution_h; - packet.resolution_v = resolution_v; - packet.rotation = rotation; - packet.hfov = hfov; - packet.stream_id = stream_id; - packet.count = count; - packet.type = type; - mav_array_memcpy(packet.name, name, sizeof(char)*32); - mav_array_memcpy(packet.uri, uri, sizeof(char)*160); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION_LEN, MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION_CRC); -} - -/** - * @brief Encode a video_stream_information struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param video_stream_information C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_video_stream_information_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_video_stream_information_t* video_stream_information) -{ - return mavlink_msg_video_stream_information_pack(system_id, component_id, msg, video_stream_information->stream_id, video_stream_information->count, video_stream_information->type, video_stream_information->flags, video_stream_information->framerate, video_stream_information->resolution_h, video_stream_information->resolution_v, video_stream_information->bitrate, video_stream_information->rotation, video_stream_information->hfov, video_stream_information->name, video_stream_information->uri); -} - -/** - * @brief Encode a video_stream_information struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param video_stream_information C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_video_stream_information_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_video_stream_information_t* video_stream_information) -{ - return mavlink_msg_video_stream_information_pack_chan(system_id, component_id, chan, msg, video_stream_information->stream_id, video_stream_information->count, video_stream_information->type, video_stream_information->flags, video_stream_information->framerate, video_stream_information->resolution_h, video_stream_information->resolution_v, video_stream_information->bitrate, video_stream_information->rotation, video_stream_information->hfov, video_stream_information->name, video_stream_information->uri); -} - -/** - * @brief Send a video_stream_information message - * @param chan MAVLink channel to send the message - * - * @param stream_id Video Stream ID (1 for first, 2 for second, etc.) - * @param count Number of streams available. - * @param type Type of stream. - * @param flags Bitmap of stream status flags. - * @param framerate [Hz] Frame rate. - * @param resolution_h [pix] Horizontal resolution. - * @param resolution_v [pix] Vertical resolution. - * @param bitrate [bits/s] Bit rate. - * @param rotation [deg] Video image rotation clockwise. - * @param hfov [deg] Horizontal Field of view. - * @param name Stream name. - * @param uri Video stream URI (TCP or RTSP URI ground station should connect to) or port number (UDP port ground station should listen to). - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_video_stream_information_send(mavlink_channel_t chan, uint8_t stream_id, uint8_t count, uint8_t type, uint16_t flags, float framerate, uint16_t resolution_h, uint16_t resolution_v, uint32_t bitrate, uint16_t rotation, uint16_t hfov, const char *name, const char *uri) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION_LEN]; - _mav_put_float(buf, 0, framerate); - _mav_put_uint32_t(buf, 4, bitrate); - _mav_put_uint16_t(buf, 8, flags); - _mav_put_uint16_t(buf, 10, resolution_h); - _mav_put_uint16_t(buf, 12, resolution_v); - _mav_put_uint16_t(buf, 14, rotation); - _mav_put_uint16_t(buf, 16, hfov); - _mav_put_uint8_t(buf, 18, stream_id); - _mav_put_uint8_t(buf, 19, count); - _mav_put_uint8_t(buf, 20, type); - _mav_put_char_array(buf, 21, name, 32); - _mav_put_char_array(buf, 53, uri, 160); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION, buf, MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION_LEN, MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION_CRC); -#else - mavlink_video_stream_information_t packet; - packet.framerate = framerate; - packet.bitrate = bitrate; - packet.flags = flags; - packet.resolution_h = resolution_h; - packet.resolution_v = resolution_v; - packet.rotation = rotation; - packet.hfov = hfov; - packet.stream_id = stream_id; - packet.count = count; - packet.type = type; - mav_array_memcpy(packet.name, name, sizeof(char)*32); - mav_array_memcpy(packet.uri, uri, sizeof(char)*160); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION, (const char *)&packet, MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION_LEN, MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION_CRC); -#endif -} - -/** - * @brief Send a video_stream_information message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_video_stream_information_send_struct(mavlink_channel_t chan, const mavlink_video_stream_information_t* video_stream_information) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_video_stream_information_send(chan, video_stream_information->stream_id, video_stream_information->count, video_stream_information->type, video_stream_information->flags, video_stream_information->framerate, video_stream_information->resolution_h, video_stream_information->resolution_v, video_stream_information->bitrate, video_stream_information->rotation, video_stream_information->hfov, video_stream_information->name, video_stream_information->uri); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION, (const char *)video_stream_information, MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION_LEN, MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION_CRC); -#endif -} - -#if MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_video_stream_information_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t stream_id, uint8_t count, uint8_t type, uint16_t flags, float framerate, uint16_t resolution_h, uint16_t resolution_v, uint32_t bitrate, uint16_t rotation, uint16_t hfov, const char *name, const char *uri) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_float(buf, 0, framerate); - _mav_put_uint32_t(buf, 4, bitrate); - _mav_put_uint16_t(buf, 8, flags); - _mav_put_uint16_t(buf, 10, resolution_h); - _mav_put_uint16_t(buf, 12, resolution_v); - _mav_put_uint16_t(buf, 14, rotation); - _mav_put_uint16_t(buf, 16, hfov); - _mav_put_uint8_t(buf, 18, stream_id); - _mav_put_uint8_t(buf, 19, count); - _mav_put_uint8_t(buf, 20, type); - _mav_put_char_array(buf, 21, name, 32); - _mav_put_char_array(buf, 53, uri, 160); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION, buf, MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION_LEN, MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION_CRC); -#else - mavlink_video_stream_information_t *packet = (mavlink_video_stream_information_t *)msgbuf; - packet->framerate = framerate; - packet->bitrate = bitrate; - packet->flags = flags; - packet->resolution_h = resolution_h; - packet->resolution_v = resolution_v; - packet->rotation = rotation; - packet->hfov = hfov; - packet->stream_id = stream_id; - packet->count = count; - packet->type = type; - mav_array_memcpy(packet->name, name, sizeof(char)*32); - mav_array_memcpy(packet->uri, uri, sizeof(char)*160); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION, (const char *)packet, MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION_LEN, MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION_CRC); -#endif -} -#endif - -#endif - -// MESSAGE VIDEO_STREAM_INFORMATION UNPACKING - - -/** - * @brief Get field stream_id from video_stream_information message - * - * @return Video Stream ID (1 for first, 2 for second, etc.) - */ -static inline uint8_t mavlink_msg_video_stream_information_get_stream_id(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 18); -} - -/** - * @brief Get field count from video_stream_information message - * - * @return Number of streams available. - */ -static inline uint8_t mavlink_msg_video_stream_information_get_count(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 19); -} - -/** - * @brief Get field type from video_stream_information message - * - * @return Type of stream. - */ -static inline uint8_t mavlink_msg_video_stream_information_get_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 20); -} - -/** - * @brief Get field flags from video_stream_information message - * - * @return Bitmap of stream status flags. - */ -static inline uint16_t mavlink_msg_video_stream_information_get_flags(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 8); -} - -/** - * @brief Get field framerate from video_stream_information message - * - * @return [Hz] Frame rate. - */ -static inline float mavlink_msg_video_stream_information_get_framerate(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 0); -} - -/** - * @brief Get field resolution_h from video_stream_information message - * - * @return [pix] Horizontal resolution. - */ -static inline uint16_t mavlink_msg_video_stream_information_get_resolution_h(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 10); -} - -/** - * @brief Get field resolution_v from video_stream_information message - * - * @return [pix] Vertical resolution. - */ -static inline uint16_t mavlink_msg_video_stream_information_get_resolution_v(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 12); -} - -/** - * @brief Get field bitrate from video_stream_information message - * - * @return [bits/s] Bit rate. - */ -static inline uint32_t mavlink_msg_video_stream_information_get_bitrate(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 4); -} - -/** - * @brief Get field rotation from video_stream_information message - * - * @return [deg] Video image rotation clockwise. - */ -static inline uint16_t mavlink_msg_video_stream_information_get_rotation(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 14); -} - -/** - * @brief Get field hfov from video_stream_information message - * - * @return [deg] Horizontal Field of view. - */ -static inline uint16_t mavlink_msg_video_stream_information_get_hfov(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 16); -} - -/** - * @brief Get field name from video_stream_information message - * - * @return Stream name. - */ -static inline uint16_t mavlink_msg_video_stream_information_get_name(const mavlink_message_t* msg, char *name) -{ - return _MAV_RETURN_char_array(msg, name, 32, 21); -} - -/** - * @brief Get field uri from video_stream_information message - * - * @return Video stream URI (TCP or RTSP URI ground station should connect to) or port number (UDP port ground station should listen to). - */ -static inline uint16_t mavlink_msg_video_stream_information_get_uri(const mavlink_message_t* msg, char *uri) -{ - return _MAV_RETURN_char_array(msg, uri, 160, 53); -} - -/** - * @brief Decode a video_stream_information message into a struct - * - * @param msg The message to decode - * @param video_stream_information C-struct to decode the message contents into - */ -static inline void mavlink_msg_video_stream_information_decode(const mavlink_message_t* msg, mavlink_video_stream_information_t* video_stream_information) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - video_stream_information->framerate = mavlink_msg_video_stream_information_get_framerate(msg); - video_stream_information->bitrate = mavlink_msg_video_stream_information_get_bitrate(msg); - video_stream_information->flags = mavlink_msg_video_stream_information_get_flags(msg); - video_stream_information->resolution_h = mavlink_msg_video_stream_information_get_resolution_h(msg); - video_stream_information->resolution_v = mavlink_msg_video_stream_information_get_resolution_v(msg); - video_stream_information->rotation = mavlink_msg_video_stream_information_get_rotation(msg); - video_stream_information->hfov = mavlink_msg_video_stream_information_get_hfov(msg); - video_stream_information->stream_id = mavlink_msg_video_stream_information_get_stream_id(msg); - video_stream_information->count = mavlink_msg_video_stream_information_get_count(msg); - video_stream_information->type = mavlink_msg_video_stream_information_get_type(msg); - mavlink_msg_video_stream_information_get_name(msg, video_stream_information->name); - mavlink_msg_video_stream_information_get_uri(msg, video_stream_information->uri); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION_LEN? msg->len : MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION_LEN; - memset(video_stream_information, 0, MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION_LEN); - memcpy(video_stream_information, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_video_stream_status.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_video_stream_status.h deleted file mode 100644 index 8058b05f..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_video_stream_status.h +++ /dev/null @@ -1,388 +0,0 @@ -#pragma once -// MESSAGE VIDEO_STREAM_STATUS PACKING - -#define MAVLINK_MSG_ID_VIDEO_STREAM_STATUS 270 - - -typedef struct __mavlink_video_stream_status_t { - float framerate; /*< [Hz] Frame rate*/ - uint32_t bitrate; /*< [bits/s] Bit rate*/ - uint16_t flags; /*< Bitmap of stream status flags*/ - uint16_t resolution_h; /*< [pix] Horizontal resolution*/ - uint16_t resolution_v; /*< [pix] Vertical resolution*/ - uint16_t rotation; /*< [deg] Video image rotation clockwise*/ - uint16_t hfov; /*< [deg] Horizontal Field of view*/ - uint8_t stream_id; /*< Video Stream ID (1 for first, 2 for second, etc.)*/ -} mavlink_video_stream_status_t; - -#define MAVLINK_MSG_ID_VIDEO_STREAM_STATUS_LEN 19 -#define MAVLINK_MSG_ID_VIDEO_STREAM_STATUS_MIN_LEN 19 -#define MAVLINK_MSG_ID_270_LEN 19 -#define MAVLINK_MSG_ID_270_MIN_LEN 19 - -#define MAVLINK_MSG_ID_VIDEO_STREAM_STATUS_CRC 59 -#define MAVLINK_MSG_ID_270_CRC 59 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_VIDEO_STREAM_STATUS { \ - 270, \ - "VIDEO_STREAM_STATUS", \ - 8, \ - { { "stream_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 18, offsetof(mavlink_video_stream_status_t, stream_id) }, \ - { "flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_video_stream_status_t, flags) }, \ - { "framerate", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_video_stream_status_t, framerate) }, \ - { "resolution_h", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_video_stream_status_t, resolution_h) }, \ - { "resolution_v", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_video_stream_status_t, resolution_v) }, \ - { "bitrate", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_video_stream_status_t, bitrate) }, \ - { "rotation", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_video_stream_status_t, rotation) }, \ - { "hfov", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_video_stream_status_t, hfov) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_VIDEO_STREAM_STATUS { \ - "VIDEO_STREAM_STATUS", \ - 8, \ - { { "stream_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 18, offsetof(mavlink_video_stream_status_t, stream_id) }, \ - { "flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_video_stream_status_t, flags) }, \ - { "framerate", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_video_stream_status_t, framerate) }, \ - { "resolution_h", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_video_stream_status_t, resolution_h) }, \ - { "resolution_v", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_video_stream_status_t, resolution_v) }, \ - { "bitrate", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_video_stream_status_t, bitrate) }, \ - { "rotation", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_video_stream_status_t, rotation) }, \ - { "hfov", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_video_stream_status_t, hfov) }, \ - } \ -} -#endif - -/** - * @brief Pack a video_stream_status message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param stream_id Video Stream ID (1 for first, 2 for second, etc.) - * @param flags Bitmap of stream status flags - * @param framerate [Hz] Frame rate - * @param resolution_h [pix] Horizontal resolution - * @param resolution_v [pix] Vertical resolution - * @param bitrate [bits/s] Bit rate - * @param rotation [deg] Video image rotation clockwise - * @param hfov [deg] Horizontal Field of view - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_video_stream_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t stream_id, uint16_t flags, float framerate, uint16_t resolution_h, uint16_t resolution_v, uint32_t bitrate, uint16_t rotation, uint16_t hfov) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_VIDEO_STREAM_STATUS_LEN]; - _mav_put_float(buf, 0, framerate); - _mav_put_uint32_t(buf, 4, bitrate); - _mav_put_uint16_t(buf, 8, flags); - _mav_put_uint16_t(buf, 10, resolution_h); - _mav_put_uint16_t(buf, 12, resolution_v); - _mav_put_uint16_t(buf, 14, rotation); - _mav_put_uint16_t(buf, 16, hfov); - _mav_put_uint8_t(buf, 18, stream_id); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VIDEO_STREAM_STATUS_LEN); -#else - mavlink_video_stream_status_t packet; - packet.framerate = framerate; - packet.bitrate = bitrate; - packet.flags = flags; - packet.resolution_h = resolution_h; - packet.resolution_v = resolution_v; - packet.rotation = rotation; - packet.hfov = hfov; - packet.stream_id = stream_id; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VIDEO_STREAM_STATUS_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_VIDEO_STREAM_STATUS; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_VIDEO_STREAM_STATUS_MIN_LEN, MAVLINK_MSG_ID_VIDEO_STREAM_STATUS_LEN, MAVLINK_MSG_ID_VIDEO_STREAM_STATUS_CRC); -} - -/** - * @brief Pack a video_stream_status message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param stream_id Video Stream ID (1 for first, 2 for second, etc.) - * @param flags Bitmap of stream status flags - * @param framerate [Hz] Frame rate - * @param resolution_h [pix] Horizontal resolution - * @param resolution_v [pix] Vertical resolution - * @param bitrate [bits/s] Bit rate - * @param rotation [deg] Video image rotation clockwise - * @param hfov [deg] Horizontal Field of view - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_video_stream_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t stream_id,uint16_t flags,float framerate,uint16_t resolution_h,uint16_t resolution_v,uint32_t bitrate,uint16_t rotation,uint16_t hfov) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_VIDEO_STREAM_STATUS_LEN]; - _mav_put_float(buf, 0, framerate); - _mav_put_uint32_t(buf, 4, bitrate); - _mav_put_uint16_t(buf, 8, flags); - _mav_put_uint16_t(buf, 10, resolution_h); - _mav_put_uint16_t(buf, 12, resolution_v); - _mav_put_uint16_t(buf, 14, rotation); - _mav_put_uint16_t(buf, 16, hfov); - _mav_put_uint8_t(buf, 18, stream_id); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VIDEO_STREAM_STATUS_LEN); -#else - mavlink_video_stream_status_t packet; - packet.framerate = framerate; - packet.bitrate = bitrate; - packet.flags = flags; - packet.resolution_h = resolution_h; - packet.resolution_v = resolution_v; - packet.rotation = rotation; - packet.hfov = hfov; - packet.stream_id = stream_id; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VIDEO_STREAM_STATUS_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_VIDEO_STREAM_STATUS; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_VIDEO_STREAM_STATUS_MIN_LEN, MAVLINK_MSG_ID_VIDEO_STREAM_STATUS_LEN, MAVLINK_MSG_ID_VIDEO_STREAM_STATUS_CRC); -} - -/** - * @brief Encode a video_stream_status struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param video_stream_status C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_video_stream_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_video_stream_status_t* video_stream_status) -{ - return mavlink_msg_video_stream_status_pack(system_id, component_id, msg, video_stream_status->stream_id, video_stream_status->flags, video_stream_status->framerate, video_stream_status->resolution_h, video_stream_status->resolution_v, video_stream_status->bitrate, video_stream_status->rotation, video_stream_status->hfov); -} - -/** - * @brief Encode a video_stream_status struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param video_stream_status C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_video_stream_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_video_stream_status_t* video_stream_status) -{ - return mavlink_msg_video_stream_status_pack_chan(system_id, component_id, chan, msg, video_stream_status->stream_id, video_stream_status->flags, video_stream_status->framerate, video_stream_status->resolution_h, video_stream_status->resolution_v, video_stream_status->bitrate, video_stream_status->rotation, video_stream_status->hfov); -} - -/** - * @brief Send a video_stream_status message - * @param chan MAVLink channel to send the message - * - * @param stream_id Video Stream ID (1 for first, 2 for second, etc.) - * @param flags Bitmap of stream status flags - * @param framerate [Hz] Frame rate - * @param resolution_h [pix] Horizontal resolution - * @param resolution_v [pix] Vertical resolution - * @param bitrate [bits/s] Bit rate - * @param rotation [deg] Video image rotation clockwise - * @param hfov [deg] Horizontal Field of view - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_video_stream_status_send(mavlink_channel_t chan, uint8_t stream_id, uint16_t flags, float framerate, uint16_t resolution_h, uint16_t resolution_v, uint32_t bitrate, uint16_t rotation, uint16_t hfov) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_VIDEO_STREAM_STATUS_LEN]; - _mav_put_float(buf, 0, framerate); - _mav_put_uint32_t(buf, 4, bitrate); - _mav_put_uint16_t(buf, 8, flags); - _mav_put_uint16_t(buf, 10, resolution_h); - _mav_put_uint16_t(buf, 12, resolution_v); - _mav_put_uint16_t(buf, 14, rotation); - _mav_put_uint16_t(buf, 16, hfov); - _mav_put_uint8_t(buf, 18, stream_id); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VIDEO_STREAM_STATUS, buf, MAVLINK_MSG_ID_VIDEO_STREAM_STATUS_MIN_LEN, MAVLINK_MSG_ID_VIDEO_STREAM_STATUS_LEN, MAVLINK_MSG_ID_VIDEO_STREAM_STATUS_CRC); -#else - mavlink_video_stream_status_t packet; - packet.framerate = framerate; - packet.bitrate = bitrate; - packet.flags = flags; - packet.resolution_h = resolution_h; - packet.resolution_v = resolution_v; - packet.rotation = rotation; - packet.hfov = hfov; - packet.stream_id = stream_id; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VIDEO_STREAM_STATUS, (const char *)&packet, MAVLINK_MSG_ID_VIDEO_STREAM_STATUS_MIN_LEN, MAVLINK_MSG_ID_VIDEO_STREAM_STATUS_LEN, MAVLINK_MSG_ID_VIDEO_STREAM_STATUS_CRC); -#endif -} - -/** - * @brief Send a video_stream_status message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_video_stream_status_send_struct(mavlink_channel_t chan, const mavlink_video_stream_status_t* video_stream_status) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_video_stream_status_send(chan, video_stream_status->stream_id, video_stream_status->flags, video_stream_status->framerate, video_stream_status->resolution_h, video_stream_status->resolution_v, video_stream_status->bitrate, video_stream_status->rotation, video_stream_status->hfov); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VIDEO_STREAM_STATUS, (const char *)video_stream_status, MAVLINK_MSG_ID_VIDEO_STREAM_STATUS_MIN_LEN, MAVLINK_MSG_ID_VIDEO_STREAM_STATUS_LEN, MAVLINK_MSG_ID_VIDEO_STREAM_STATUS_CRC); -#endif -} - -#if MAVLINK_MSG_ID_VIDEO_STREAM_STATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_video_stream_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t stream_id, uint16_t flags, float framerate, uint16_t resolution_h, uint16_t resolution_v, uint32_t bitrate, uint16_t rotation, uint16_t hfov) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_float(buf, 0, framerate); - _mav_put_uint32_t(buf, 4, bitrate); - _mav_put_uint16_t(buf, 8, flags); - _mav_put_uint16_t(buf, 10, resolution_h); - _mav_put_uint16_t(buf, 12, resolution_v); - _mav_put_uint16_t(buf, 14, rotation); - _mav_put_uint16_t(buf, 16, hfov); - _mav_put_uint8_t(buf, 18, stream_id); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VIDEO_STREAM_STATUS, buf, MAVLINK_MSG_ID_VIDEO_STREAM_STATUS_MIN_LEN, MAVLINK_MSG_ID_VIDEO_STREAM_STATUS_LEN, MAVLINK_MSG_ID_VIDEO_STREAM_STATUS_CRC); -#else - mavlink_video_stream_status_t *packet = (mavlink_video_stream_status_t *)msgbuf; - packet->framerate = framerate; - packet->bitrate = bitrate; - packet->flags = flags; - packet->resolution_h = resolution_h; - packet->resolution_v = resolution_v; - packet->rotation = rotation; - packet->hfov = hfov; - packet->stream_id = stream_id; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VIDEO_STREAM_STATUS, (const char *)packet, MAVLINK_MSG_ID_VIDEO_STREAM_STATUS_MIN_LEN, MAVLINK_MSG_ID_VIDEO_STREAM_STATUS_LEN, MAVLINK_MSG_ID_VIDEO_STREAM_STATUS_CRC); -#endif -} -#endif - -#endif - -// MESSAGE VIDEO_STREAM_STATUS UNPACKING - - -/** - * @brief Get field stream_id from video_stream_status message - * - * @return Video Stream ID (1 for first, 2 for second, etc.) - */ -static inline uint8_t mavlink_msg_video_stream_status_get_stream_id(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 18); -} - -/** - * @brief Get field flags from video_stream_status message - * - * @return Bitmap of stream status flags - */ -static inline uint16_t mavlink_msg_video_stream_status_get_flags(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 8); -} - -/** - * @brief Get field framerate from video_stream_status message - * - * @return [Hz] Frame rate - */ -static inline float mavlink_msg_video_stream_status_get_framerate(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 0); -} - -/** - * @brief Get field resolution_h from video_stream_status message - * - * @return [pix] Horizontal resolution - */ -static inline uint16_t mavlink_msg_video_stream_status_get_resolution_h(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 10); -} - -/** - * @brief Get field resolution_v from video_stream_status message - * - * @return [pix] Vertical resolution - */ -static inline uint16_t mavlink_msg_video_stream_status_get_resolution_v(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 12); -} - -/** - * @brief Get field bitrate from video_stream_status message - * - * @return [bits/s] Bit rate - */ -static inline uint32_t mavlink_msg_video_stream_status_get_bitrate(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 4); -} - -/** - * @brief Get field rotation from video_stream_status message - * - * @return [deg] Video image rotation clockwise - */ -static inline uint16_t mavlink_msg_video_stream_status_get_rotation(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 14); -} - -/** - * @brief Get field hfov from video_stream_status message - * - * @return [deg] Horizontal Field of view - */ -static inline uint16_t mavlink_msg_video_stream_status_get_hfov(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 16); -} - -/** - * @brief Decode a video_stream_status message into a struct - * - * @param msg The message to decode - * @param video_stream_status C-struct to decode the message contents into - */ -static inline void mavlink_msg_video_stream_status_decode(const mavlink_message_t* msg, mavlink_video_stream_status_t* video_stream_status) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - video_stream_status->framerate = mavlink_msg_video_stream_status_get_framerate(msg); - video_stream_status->bitrate = mavlink_msg_video_stream_status_get_bitrate(msg); - video_stream_status->flags = mavlink_msg_video_stream_status_get_flags(msg); - video_stream_status->resolution_h = mavlink_msg_video_stream_status_get_resolution_h(msg); - video_stream_status->resolution_v = mavlink_msg_video_stream_status_get_resolution_v(msg); - video_stream_status->rotation = mavlink_msg_video_stream_status_get_rotation(msg); - video_stream_status->hfov = mavlink_msg_video_stream_status_get_hfov(msg); - video_stream_status->stream_id = mavlink_msg_video_stream_status_get_stream_id(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_VIDEO_STREAM_STATUS_LEN? msg->len : MAVLINK_MSG_ID_VIDEO_STREAM_STATUS_LEN; - memset(video_stream_status, 0, MAVLINK_MSG_ID_VIDEO_STREAM_STATUS_LEN); - memcpy(video_stream_status, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_vision_position_estimate.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_vision_position_estimate.h deleted file mode 100644 index e0ebff7d..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_vision_position_estimate.h +++ /dev/null @@ -1,405 +0,0 @@ -#pragma once -// MESSAGE VISION_POSITION_ESTIMATE PACKING - -#define MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE 102 - - -typedef struct __mavlink_vision_position_estimate_t { - uint64_t usec; /*< [us] Timestamp (UNIX time or time since system boot)*/ - float x; /*< [m] Local X position*/ - float y; /*< [m] Local Y position*/ - float z; /*< [m] Local Z position*/ - float roll; /*< [rad] Roll angle*/ - float pitch; /*< [rad] Pitch angle*/ - float yaw; /*< [rad] Yaw angle*/ - float covariance[21]; /*< Row-major representation of pose 6x6 cross-covariance matrix upper right triangle (states: x, y, z, roll, pitch, yaw; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array.*/ - uint8_t reset_counter; /*< Estimate reset counter. This should be incremented when the estimate resets in any of the dimensions (position, velocity, attitude, angular speed). This is designed to be used when e.g an external SLAM system detects a loop-closure and the estimate jumps.*/ -} mavlink_vision_position_estimate_t; - -#define MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN 117 -#define MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_MIN_LEN 32 -#define MAVLINK_MSG_ID_102_LEN 117 -#define MAVLINK_MSG_ID_102_MIN_LEN 32 - -#define MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_CRC 158 -#define MAVLINK_MSG_ID_102_CRC 158 - -#define MAVLINK_MSG_VISION_POSITION_ESTIMATE_FIELD_COVARIANCE_LEN 21 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_VISION_POSITION_ESTIMATE { \ - 102, \ - "VISION_POSITION_ESTIMATE", \ - 9, \ - { { "usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_vision_position_estimate_t, usec) }, \ - { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_vision_position_estimate_t, x) }, \ - { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_vision_position_estimate_t, y) }, \ - { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_vision_position_estimate_t, z) }, \ - { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_vision_position_estimate_t, roll) }, \ - { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_vision_position_estimate_t, pitch) }, \ - { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_vision_position_estimate_t, yaw) }, \ - { "covariance", NULL, MAVLINK_TYPE_FLOAT, 21, 32, offsetof(mavlink_vision_position_estimate_t, covariance) }, \ - { "reset_counter", NULL, MAVLINK_TYPE_UINT8_T, 0, 116, offsetof(mavlink_vision_position_estimate_t, reset_counter) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_VISION_POSITION_ESTIMATE { \ - "VISION_POSITION_ESTIMATE", \ - 9, \ - { { "usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_vision_position_estimate_t, usec) }, \ - { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_vision_position_estimate_t, x) }, \ - { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_vision_position_estimate_t, y) }, \ - { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_vision_position_estimate_t, z) }, \ - { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_vision_position_estimate_t, roll) }, \ - { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_vision_position_estimate_t, pitch) }, \ - { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_vision_position_estimate_t, yaw) }, \ - { "covariance", NULL, MAVLINK_TYPE_FLOAT, 21, 32, offsetof(mavlink_vision_position_estimate_t, covariance) }, \ - { "reset_counter", NULL, MAVLINK_TYPE_UINT8_T, 0, 116, offsetof(mavlink_vision_position_estimate_t, reset_counter) }, \ - } \ -} -#endif - -/** - * @brief Pack a vision_position_estimate message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param usec [us] Timestamp (UNIX time or time since system boot) - * @param x [m] Local X position - * @param y [m] Local Y position - * @param z [m] Local Z position - * @param roll [rad] Roll angle - * @param pitch [rad] Pitch angle - * @param yaw [rad] Yaw angle - * @param covariance Row-major representation of pose 6x6 cross-covariance matrix upper right triangle (states: x, y, z, roll, pitch, yaw; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array. - * @param reset_counter Estimate reset counter. This should be incremented when the estimate resets in any of the dimensions (position, velocity, attitude, angular speed). This is designed to be used when e.g an external SLAM system detects a loop-closure and the estimate jumps. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_vision_position_estimate_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint64_t usec, float x, float y, float z, float roll, float pitch, float yaw, const float *covariance, uint8_t reset_counter) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN]; - _mav_put_uint64_t(buf, 0, usec); - _mav_put_float(buf, 8, x); - _mav_put_float(buf, 12, y); - _mav_put_float(buf, 16, z); - _mav_put_float(buf, 20, roll); - _mav_put_float(buf, 24, pitch); - _mav_put_float(buf, 28, yaw); - _mav_put_uint8_t(buf, 116, reset_counter); - _mav_put_float_array(buf, 32, covariance, 21); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN); -#else - mavlink_vision_position_estimate_t packet; - packet.usec = usec; - packet.x = x; - packet.y = y; - packet.z = z; - packet.roll = roll; - packet.pitch = pitch; - packet.yaw = yaw; - packet.reset_counter = reset_counter; - mav_array_memcpy(packet.covariance, covariance, sizeof(float)*21); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_MIN_LEN, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_CRC); -} - -/** - * @brief Pack a vision_position_estimate message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param usec [us] Timestamp (UNIX time or time since system boot) - * @param x [m] Local X position - * @param y [m] Local Y position - * @param z [m] Local Z position - * @param roll [rad] Roll angle - * @param pitch [rad] Pitch angle - * @param yaw [rad] Yaw angle - * @param covariance Row-major representation of pose 6x6 cross-covariance matrix upper right triangle (states: x, y, z, roll, pitch, yaw; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array. - * @param reset_counter Estimate reset counter. This should be incremented when the estimate resets in any of the dimensions (position, velocity, attitude, angular speed). This is designed to be used when e.g an external SLAM system detects a loop-closure and the estimate jumps. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_vision_position_estimate_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint64_t usec,float x,float y,float z,float roll,float pitch,float yaw,const float *covariance,uint8_t reset_counter) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN]; - _mav_put_uint64_t(buf, 0, usec); - _mav_put_float(buf, 8, x); - _mav_put_float(buf, 12, y); - _mav_put_float(buf, 16, z); - _mav_put_float(buf, 20, roll); - _mav_put_float(buf, 24, pitch); - _mav_put_float(buf, 28, yaw); - _mav_put_uint8_t(buf, 116, reset_counter); - _mav_put_float_array(buf, 32, covariance, 21); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN); -#else - mavlink_vision_position_estimate_t packet; - packet.usec = usec; - packet.x = x; - packet.y = y; - packet.z = z; - packet.roll = roll; - packet.pitch = pitch; - packet.yaw = yaw; - packet.reset_counter = reset_counter; - mav_array_memcpy(packet.covariance, covariance, sizeof(float)*21); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_MIN_LEN, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_CRC); -} - -/** - * @brief Encode a vision_position_estimate struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param vision_position_estimate C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_vision_position_estimate_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_vision_position_estimate_t* vision_position_estimate) -{ - return mavlink_msg_vision_position_estimate_pack(system_id, component_id, msg, vision_position_estimate->usec, vision_position_estimate->x, vision_position_estimate->y, vision_position_estimate->z, vision_position_estimate->roll, vision_position_estimate->pitch, vision_position_estimate->yaw, vision_position_estimate->covariance, vision_position_estimate->reset_counter); -} - -/** - * @brief Encode a vision_position_estimate struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param vision_position_estimate C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_vision_position_estimate_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_vision_position_estimate_t* vision_position_estimate) -{ - return mavlink_msg_vision_position_estimate_pack_chan(system_id, component_id, chan, msg, vision_position_estimate->usec, vision_position_estimate->x, vision_position_estimate->y, vision_position_estimate->z, vision_position_estimate->roll, vision_position_estimate->pitch, vision_position_estimate->yaw, vision_position_estimate->covariance, vision_position_estimate->reset_counter); -} - -/** - * @brief Send a vision_position_estimate message - * @param chan MAVLink channel to send the message - * - * @param usec [us] Timestamp (UNIX time or time since system boot) - * @param x [m] Local X position - * @param y [m] Local Y position - * @param z [m] Local Z position - * @param roll [rad] Roll angle - * @param pitch [rad] Pitch angle - * @param yaw [rad] Yaw angle - * @param covariance Row-major representation of pose 6x6 cross-covariance matrix upper right triangle (states: x, y, z, roll, pitch, yaw; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array. - * @param reset_counter Estimate reset counter. This should be incremented when the estimate resets in any of the dimensions (position, velocity, attitude, angular speed). This is designed to be used when e.g an external SLAM system detects a loop-closure and the estimate jumps. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_vision_position_estimate_send(mavlink_channel_t chan, uint64_t usec, float x, float y, float z, float roll, float pitch, float yaw, const float *covariance, uint8_t reset_counter) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN]; - _mav_put_uint64_t(buf, 0, usec); - _mav_put_float(buf, 8, x); - _mav_put_float(buf, 12, y); - _mav_put_float(buf, 16, z); - _mav_put_float(buf, 20, roll); - _mav_put_float(buf, 24, pitch); - _mav_put_float(buf, 28, yaw); - _mav_put_uint8_t(buf, 116, reset_counter); - _mav_put_float_array(buf, 32, covariance, 21); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE, buf, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_MIN_LEN, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_CRC); -#else - mavlink_vision_position_estimate_t packet; - packet.usec = usec; - packet.x = x; - packet.y = y; - packet.z = z; - packet.roll = roll; - packet.pitch = pitch; - packet.yaw = yaw; - packet.reset_counter = reset_counter; - mav_array_memcpy(packet.covariance, covariance, sizeof(float)*21); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE, (const char *)&packet, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_MIN_LEN, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_CRC); -#endif -} - -/** - * @brief Send a vision_position_estimate message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_vision_position_estimate_send_struct(mavlink_channel_t chan, const mavlink_vision_position_estimate_t* vision_position_estimate) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_vision_position_estimate_send(chan, vision_position_estimate->usec, vision_position_estimate->x, vision_position_estimate->y, vision_position_estimate->z, vision_position_estimate->roll, vision_position_estimate->pitch, vision_position_estimate->yaw, vision_position_estimate->covariance, vision_position_estimate->reset_counter); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE, (const char *)vision_position_estimate, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_MIN_LEN, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_CRC); -#endif -} - -#if MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_vision_position_estimate_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t usec, float x, float y, float z, float roll, float pitch, float yaw, const float *covariance, uint8_t reset_counter) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, usec); - _mav_put_float(buf, 8, x); - _mav_put_float(buf, 12, y); - _mav_put_float(buf, 16, z); - _mav_put_float(buf, 20, roll); - _mav_put_float(buf, 24, pitch); - _mav_put_float(buf, 28, yaw); - _mav_put_uint8_t(buf, 116, reset_counter); - _mav_put_float_array(buf, 32, covariance, 21); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE, buf, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_MIN_LEN, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_CRC); -#else - mavlink_vision_position_estimate_t *packet = (mavlink_vision_position_estimate_t *)msgbuf; - packet->usec = usec; - packet->x = x; - packet->y = y; - packet->z = z; - packet->roll = roll; - packet->pitch = pitch; - packet->yaw = yaw; - packet->reset_counter = reset_counter; - mav_array_memcpy(packet->covariance, covariance, sizeof(float)*21); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE, (const char *)packet, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_MIN_LEN, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_CRC); -#endif -} -#endif - -#endif - -// MESSAGE VISION_POSITION_ESTIMATE UNPACKING - - -/** - * @brief Get field usec from vision_position_estimate message - * - * @return [us] Timestamp (UNIX time or time since system boot) - */ -static inline uint64_t mavlink_msg_vision_position_estimate_get_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field x from vision_position_estimate message - * - * @return [m] Local X position - */ -static inline float mavlink_msg_vision_position_estimate_get_x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field y from vision_position_estimate message - * - * @return [m] Local Y position - */ -static inline float mavlink_msg_vision_position_estimate_get_y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field z from vision_position_estimate message - * - * @return [m] Local Z position - */ -static inline float mavlink_msg_vision_position_estimate_get_z(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field roll from vision_position_estimate message - * - * @return [rad] Roll angle - */ -static inline float mavlink_msg_vision_position_estimate_get_roll(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Get field pitch from vision_position_estimate message - * - * @return [rad] Pitch angle - */ -static inline float mavlink_msg_vision_position_estimate_get_pitch(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Get field yaw from vision_position_estimate message - * - * @return [rad] Yaw angle - */ -static inline float mavlink_msg_vision_position_estimate_get_yaw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 28); -} - -/** - * @brief Get field covariance from vision_position_estimate message - * - * @return Row-major representation of pose 6x6 cross-covariance matrix upper right triangle (states: x, y, z, roll, pitch, yaw; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array. - */ -static inline uint16_t mavlink_msg_vision_position_estimate_get_covariance(const mavlink_message_t* msg, float *covariance) -{ - return _MAV_RETURN_float_array(msg, covariance, 21, 32); -} - -/** - * @brief Get field reset_counter from vision_position_estimate message - * - * @return Estimate reset counter. This should be incremented when the estimate resets in any of the dimensions (position, velocity, attitude, angular speed). This is designed to be used when e.g an external SLAM system detects a loop-closure and the estimate jumps. - */ -static inline uint8_t mavlink_msg_vision_position_estimate_get_reset_counter(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 116); -} - -/** - * @brief Decode a vision_position_estimate message into a struct - * - * @param msg The message to decode - * @param vision_position_estimate C-struct to decode the message contents into - */ -static inline void mavlink_msg_vision_position_estimate_decode(const mavlink_message_t* msg, mavlink_vision_position_estimate_t* vision_position_estimate) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - vision_position_estimate->usec = mavlink_msg_vision_position_estimate_get_usec(msg); - vision_position_estimate->x = mavlink_msg_vision_position_estimate_get_x(msg); - vision_position_estimate->y = mavlink_msg_vision_position_estimate_get_y(msg); - vision_position_estimate->z = mavlink_msg_vision_position_estimate_get_z(msg); - vision_position_estimate->roll = mavlink_msg_vision_position_estimate_get_roll(msg); - vision_position_estimate->pitch = mavlink_msg_vision_position_estimate_get_pitch(msg); - vision_position_estimate->yaw = mavlink_msg_vision_position_estimate_get_yaw(msg); - mavlink_msg_vision_position_estimate_get_covariance(msg, vision_position_estimate->covariance); - vision_position_estimate->reset_counter = mavlink_msg_vision_position_estimate_get_reset_counter(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN? msg->len : MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN; - memset(vision_position_estimate, 0, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN); - memcpy(vision_position_estimate, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_vision_speed_estimate.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_vision_speed_estimate.h deleted file mode 100644 index c12206a2..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_vision_speed_estimate.h +++ /dev/null @@ -1,330 +0,0 @@ -#pragma once -// MESSAGE VISION_SPEED_ESTIMATE PACKING - -#define MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE 103 - - -typedef struct __mavlink_vision_speed_estimate_t { - uint64_t usec; /*< [us] Timestamp (UNIX time or time since system boot)*/ - float x; /*< [m/s] Global X speed*/ - float y; /*< [m/s] Global Y speed*/ - float z; /*< [m/s] Global Z speed*/ - float covariance[9]; /*< Row-major representation of 3x3 linear velocity covariance matrix (states: vx, vy, vz; 1st three entries - 1st row, etc.). If unknown, assign NaN value to first element in the array.*/ - uint8_t reset_counter; /*< Estimate reset counter. This should be incremented when the estimate resets in any of the dimensions (position, velocity, attitude, angular speed). This is designed to be used when e.g an external SLAM system detects a loop-closure and the estimate jumps.*/ -} mavlink_vision_speed_estimate_t; - -#define MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN 57 -#define MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_MIN_LEN 20 -#define MAVLINK_MSG_ID_103_LEN 57 -#define MAVLINK_MSG_ID_103_MIN_LEN 20 - -#define MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_CRC 208 -#define MAVLINK_MSG_ID_103_CRC 208 - -#define MAVLINK_MSG_VISION_SPEED_ESTIMATE_FIELD_COVARIANCE_LEN 9 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_VISION_SPEED_ESTIMATE { \ - 103, \ - "VISION_SPEED_ESTIMATE", \ - 6, \ - { { "usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_vision_speed_estimate_t, usec) }, \ - { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_vision_speed_estimate_t, x) }, \ - { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_vision_speed_estimate_t, y) }, \ - { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_vision_speed_estimate_t, z) }, \ - { "covariance", NULL, MAVLINK_TYPE_FLOAT, 9, 20, offsetof(mavlink_vision_speed_estimate_t, covariance) }, \ - { "reset_counter", NULL, MAVLINK_TYPE_UINT8_T, 0, 56, offsetof(mavlink_vision_speed_estimate_t, reset_counter) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_VISION_SPEED_ESTIMATE { \ - "VISION_SPEED_ESTIMATE", \ - 6, \ - { { "usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_vision_speed_estimate_t, usec) }, \ - { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_vision_speed_estimate_t, x) }, \ - { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_vision_speed_estimate_t, y) }, \ - { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_vision_speed_estimate_t, z) }, \ - { "covariance", NULL, MAVLINK_TYPE_FLOAT, 9, 20, offsetof(mavlink_vision_speed_estimate_t, covariance) }, \ - { "reset_counter", NULL, MAVLINK_TYPE_UINT8_T, 0, 56, offsetof(mavlink_vision_speed_estimate_t, reset_counter) }, \ - } \ -} -#endif - -/** - * @brief Pack a vision_speed_estimate message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param usec [us] Timestamp (UNIX time or time since system boot) - * @param x [m/s] Global X speed - * @param y [m/s] Global Y speed - * @param z [m/s] Global Z speed - * @param covariance Row-major representation of 3x3 linear velocity covariance matrix (states: vx, vy, vz; 1st three entries - 1st row, etc.). If unknown, assign NaN value to first element in the array. - * @param reset_counter Estimate reset counter. This should be incremented when the estimate resets in any of the dimensions (position, velocity, attitude, angular speed). This is designed to be used when e.g an external SLAM system detects a loop-closure and the estimate jumps. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_vision_speed_estimate_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint64_t usec, float x, float y, float z, const float *covariance, uint8_t reset_counter) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN]; - _mav_put_uint64_t(buf, 0, usec); - _mav_put_float(buf, 8, x); - _mav_put_float(buf, 12, y); - _mav_put_float(buf, 16, z); - _mav_put_uint8_t(buf, 56, reset_counter); - _mav_put_float_array(buf, 20, covariance, 9); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN); -#else - mavlink_vision_speed_estimate_t packet; - packet.usec = usec; - packet.x = x; - packet.y = y; - packet.z = z; - packet.reset_counter = reset_counter; - mav_array_memcpy(packet.covariance, covariance, sizeof(float)*9); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_MIN_LEN, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_CRC); -} - -/** - * @brief Pack a vision_speed_estimate message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param usec [us] Timestamp (UNIX time or time since system boot) - * @param x [m/s] Global X speed - * @param y [m/s] Global Y speed - * @param z [m/s] Global Z speed - * @param covariance Row-major representation of 3x3 linear velocity covariance matrix (states: vx, vy, vz; 1st three entries - 1st row, etc.). If unknown, assign NaN value to first element in the array. - * @param reset_counter Estimate reset counter. This should be incremented when the estimate resets in any of the dimensions (position, velocity, attitude, angular speed). This is designed to be used when e.g an external SLAM system detects a loop-closure and the estimate jumps. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_vision_speed_estimate_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint64_t usec,float x,float y,float z,const float *covariance,uint8_t reset_counter) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN]; - _mav_put_uint64_t(buf, 0, usec); - _mav_put_float(buf, 8, x); - _mav_put_float(buf, 12, y); - _mav_put_float(buf, 16, z); - _mav_put_uint8_t(buf, 56, reset_counter); - _mav_put_float_array(buf, 20, covariance, 9); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN); -#else - mavlink_vision_speed_estimate_t packet; - packet.usec = usec; - packet.x = x; - packet.y = y; - packet.z = z; - packet.reset_counter = reset_counter; - mav_array_memcpy(packet.covariance, covariance, sizeof(float)*9); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_MIN_LEN, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_CRC); -} - -/** - * @brief Encode a vision_speed_estimate struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param vision_speed_estimate C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_vision_speed_estimate_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_vision_speed_estimate_t* vision_speed_estimate) -{ - return mavlink_msg_vision_speed_estimate_pack(system_id, component_id, msg, vision_speed_estimate->usec, vision_speed_estimate->x, vision_speed_estimate->y, vision_speed_estimate->z, vision_speed_estimate->covariance, vision_speed_estimate->reset_counter); -} - -/** - * @brief Encode a vision_speed_estimate struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param vision_speed_estimate C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_vision_speed_estimate_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_vision_speed_estimate_t* vision_speed_estimate) -{ - return mavlink_msg_vision_speed_estimate_pack_chan(system_id, component_id, chan, msg, vision_speed_estimate->usec, vision_speed_estimate->x, vision_speed_estimate->y, vision_speed_estimate->z, vision_speed_estimate->covariance, vision_speed_estimate->reset_counter); -} - -/** - * @brief Send a vision_speed_estimate message - * @param chan MAVLink channel to send the message - * - * @param usec [us] Timestamp (UNIX time or time since system boot) - * @param x [m/s] Global X speed - * @param y [m/s] Global Y speed - * @param z [m/s] Global Z speed - * @param covariance Row-major representation of 3x3 linear velocity covariance matrix (states: vx, vy, vz; 1st three entries - 1st row, etc.). If unknown, assign NaN value to first element in the array. - * @param reset_counter Estimate reset counter. This should be incremented when the estimate resets in any of the dimensions (position, velocity, attitude, angular speed). This is designed to be used when e.g an external SLAM system detects a loop-closure and the estimate jumps. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_vision_speed_estimate_send(mavlink_channel_t chan, uint64_t usec, float x, float y, float z, const float *covariance, uint8_t reset_counter) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN]; - _mav_put_uint64_t(buf, 0, usec); - _mav_put_float(buf, 8, x); - _mav_put_float(buf, 12, y); - _mav_put_float(buf, 16, z); - _mav_put_uint8_t(buf, 56, reset_counter); - _mav_put_float_array(buf, 20, covariance, 9); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE, buf, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_MIN_LEN, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_CRC); -#else - mavlink_vision_speed_estimate_t packet; - packet.usec = usec; - packet.x = x; - packet.y = y; - packet.z = z; - packet.reset_counter = reset_counter; - mav_array_memcpy(packet.covariance, covariance, sizeof(float)*9); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE, (const char *)&packet, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_MIN_LEN, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_CRC); -#endif -} - -/** - * @brief Send a vision_speed_estimate message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_vision_speed_estimate_send_struct(mavlink_channel_t chan, const mavlink_vision_speed_estimate_t* vision_speed_estimate) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_vision_speed_estimate_send(chan, vision_speed_estimate->usec, vision_speed_estimate->x, vision_speed_estimate->y, vision_speed_estimate->z, vision_speed_estimate->covariance, vision_speed_estimate->reset_counter); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE, (const char *)vision_speed_estimate, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_MIN_LEN, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_CRC); -#endif -} - -#if MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_vision_speed_estimate_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t usec, float x, float y, float z, const float *covariance, uint8_t reset_counter) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, usec); - _mav_put_float(buf, 8, x); - _mav_put_float(buf, 12, y); - _mav_put_float(buf, 16, z); - _mav_put_uint8_t(buf, 56, reset_counter); - _mav_put_float_array(buf, 20, covariance, 9); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE, buf, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_MIN_LEN, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_CRC); -#else - mavlink_vision_speed_estimate_t *packet = (mavlink_vision_speed_estimate_t *)msgbuf; - packet->usec = usec; - packet->x = x; - packet->y = y; - packet->z = z; - packet->reset_counter = reset_counter; - mav_array_memcpy(packet->covariance, covariance, sizeof(float)*9); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE, (const char *)packet, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_MIN_LEN, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_CRC); -#endif -} -#endif - -#endif - -// MESSAGE VISION_SPEED_ESTIMATE UNPACKING - - -/** - * @brief Get field usec from vision_speed_estimate message - * - * @return [us] Timestamp (UNIX time or time since system boot) - */ -static inline uint64_t mavlink_msg_vision_speed_estimate_get_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field x from vision_speed_estimate message - * - * @return [m/s] Global X speed - */ -static inline float mavlink_msg_vision_speed_estimate_get_x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field y from vision_speed_estimate message - * - * @return [m/s] Global Y speed - */ -static inline float mavlink_msg_vision_speed_estimate_get_y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field z from vision_speed_estimate message - * - * @return [m/s] Global Z speed - */ -static inline float mavlink_msg_vision_speed_estimate_get_z(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field covariance from vision_speed_estimate message - * - * @return Row-major representation of 3x3 linear velocity covariance matrix (states: vx, vy, vz; 1st three entries - 1st row, etc.). If unknown, assign NaN value to first element in the array. - */ -static inline uint16_t mavlink_msg_vision_speed_estimate_get_covariance(const mavlink_message_t* msg, float *covariance) -{ - return _MAV_RETURN_float_array(msg, covariance, 9, 20); -} - -/** - * @brief Get field reset_counter from vision_speed_estimate message - * - * @return Estimate reset counter. This should be incremented when the estimate resets in any of the dimensions (position, velocity, attitude, angular speed). This is designed to be used when e.g an external SLAM system detects a loop-closure and the estimate jumps. - */ -static inline uint8_t mavlink_msg_vision_speed_estimate_get_reset_counter(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 56); -} - -/** - * @brief Decode a vision_speed_estimate message into a struct - * - * @param msg The message to decode - * @param vision_speed_estimate C-struct to decode the message contents into - */ -static inline void mavlink_msg_vision_speed_estimate_decode(const mavlink_message_t* msg, mavlink_vision_speed_estimate_t* vision_speed_estimate) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - vision_speed_estimate->usec = mavlink_msg_vision_speed_estimate_get_usec(msg); - vision_speed_estimate->x = mavlink_msg_vision_speed_estimate_get_x(msg); - vision_speed_estimate->y = mavlink_msg_vision_speed_estimate_get_y(msg); - vision_speed_estimate->z = mavlink_msg_vision_speed_estimate_get_z(msg); - mavlink_msg_vision_speed_estimate_get_covariance(msg, vision_speed_estimate->covariance); - vision_speed_estimate->reset_counter = mavlink_msg_vision_speed_estimate_get_reset_counter(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN? msg->len : MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN; - memset(vision_speed_estimate, 0, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN); - memcpy(vision_speed_estimate, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_wheel_distance.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_wheel_distance.h deleted file mode 100644 index 6a177c88..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_wheel_distance.h +++ /dev/null @@ -1,255 +0,0 @@ -#pragma once -// MESSAGE WHEEL_DISTANCE PACKING - -#define MAVLINK_MSG_ID_WHEEL_DISTANCE 9000 - - -typedef struct __mavlink_wheel_distance_t { - uint64_t time_usec; /*< [us] Timestamp (synced to UNIX time or since system boot).*/ - double distance[16]; /*< [m] Distance reported by individual wheel encoders. Forward rotations increase values, reverse rotations decrease them. Not all wheels will necessarily have wheel encoders; the mapping of encoders to wheel positions must be agreed/understood by the endpoints.*/ - uint8_t count; /*< Number of wheels reported.*/ -} mavlink_wheel_distance_t; - -#define MAVLINK_MSG_ID_WHEEL_DISTANCE_LEN 137 -#define MAVLINK_MSG_ID_WHEEL_DISTANCE_MIN_LEN 137 -#define MAVLINK_MSG_ID_9000_LEN 137 -#define MAVLINK_MSG_ID_9000_MIN_LEN 137 - -#define MAVLINK_MSG_ID_WHEEL_DISTANCE_CRC 113 -#define MAVLINK_MSG_ID_9000_CRC 113 - -#define MAVLINK_MSG_WHEEL_DISTANCE_FIELD_DISTANCE_LEN 16 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_WHEEL_DISTANCE { \ - 9000, \ - "WHEEL_DISTANCE", \ - 3, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_wheel_distance_t, time_usec) }, \ - { "count", NULL, MAVLINK_TYPE_UINT8_T, 0, 136, offsetof(mavlink_wheel_distance_t, count) }, \ - { "distance", NULL, MAVLINK_TYPE_DOUBLE, 16, 8, offsetof(mavlink_wheel_distance_t, distance) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_WHEEL_DISTANCE { \ - "WHEEL_DISTANCE", \ - 3, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_wheel_distance_t, time_usec) }, \ - { "count", NULL, MAVLINK_TYPE_UINT8_T, 0, 136, offsetof(mavlink_wheel_distance_t, count) }, \ - { "distance", NULL, MAVLINK_TYPE_DOUBLE, 16, 8, offsetof(mavlink_wheel_distance_t, distance) }, \ - } \ -} -#endif - -/** - * @brief Pack a wheel_distance message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param time_usec [us] Timestamp (synced to UNIX time or since system boot). - * @param count Number of wheels reported. - * @param distance [m] Distance reported by individual wheel encoders. Forward rotations increase values, reverse rotations decrease them. Not all wheels will necessarily have wheel encoders; the mapping of encoders to wheel positions must be agreed/understood by the endpoints. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_wheel_distance_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint64_t time_usec, uint8_t count, const double *distance) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_WHEEL_DISTANCE_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint8_t(buf, 136, count); - _mav_put_double_array(buf, 8, distance, 16); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_WHEEL_DISTANCE_LEN); -#else - mavlink_wheel_distance_t packet; - packet.time_usec = time_usec; - packet.count = count; - mav_array_memcpy(packet.distance, distance, sizeof(double)*16); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_WHEEL_DISTANCE_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_WHEEL_DISTANCE; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_WHEEL_DISTANCE_MIN_LEN, MAVLINK_MSG_ID_WHEEL_DISTANCE_LEN, MAVLINK_MSG_ID_WHEEL_DISTANCE_CRC); -} - -/** - * @brief Pack a wheel_distance message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_usec [us] Timestamp (synced to UNIX time or since system boot). - * @param count Number of wheels reported. - * @param distance [m] Distance reported by individual wheel encoders. Forward rotations increase values, reverse rotations decrease them. Not all wheels will necessarily have wheel encoders; the mapping of encoders to wheel positions must be agreed/understood by the endpoints. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_wheel_distance_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint64_t time_usec,uint8_t count,const double *distance) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_WHEEL_DISTANCE_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint8_t(buf, 136, count); - _mav_put_double_array(buf, 8, distance, 16); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_WHEEL_DISTANCE_LEN); -#else - mavlink_wheel_distance_t packet; - packet.time_usec = time_usec; - packet.count = count; - mav_array_memcpy(packet.distance, distance, sizeof(double)*16); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_WHEEL_DISTANCE_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_WHEEL_DISTANCE; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_WHEEL_DISTANCE_MIN_LEN, MAVLINK_MSG_ID_WHEEL_DISTANCE_LEN, MAVLINK_MSG_ID_WHEEL_DISTANCE_CRC); -} - -/** - * @brief Encode a wheel_distance struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param wheel_distance C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_wheel_distance_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_wheel_distance_t* wheel_distance) -{ - return mavlink_msg_wheel_distance_pack(system_id, component_id, msg, wheel_distance->time_usec, wheel_distance->count, wheel_distance->distance); -} - -/** - * @brief Encode a wheel_distance struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param wheel_distance C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_wheel_distance_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_wheel_distance_t* wheel_distance) -{ - return mavlink_msg_wheel_distance_pack_chan(system_id, component_id, chan, msg, wheel_distance->time_usec, wheel_distance->count, wheel_distance->distance); -} - -/** - * @brief Send a wheel_distance message - * @param chan MAVLink channel to send the message - * - * @param time_usec [us] Timestamp (synced to UNIX time or since system boot). - * @param count Number of wheels reported. - * @param distance [m] Distance reported by individual wheel encoders. Forward rotations increase values, reverse rotations decrease them. Not all wheels will necessarily have wheel encoders; the mapping of encoders to wheel positions must be agreed/understood by the endpoints. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_wheel_distance_send(mavlink_channel_t chan, uint64_t time_usec, uint8_t count, const double *distance) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_WHEEL_DISTANCE_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint8_t(buf, 136, count); - _mav_put_double_array(buf, 8, distance, 16); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WHEEL_DISTANCE, buf, MAVLINK_MSG_ID_WHEEL_DISTANCE_MIN_LEN, MAVLINK_MSG_ID_WHEEL_DISTANCE_LEN, MAVLINK_MSG_ID_WHEEL_DISTANCE_CRC); -#else - mavlink_wheel_distance_t packet; - packet.time_usec = time_usec; - packet.count = count; - mav_array_memcpy(packet.distance, distance, sizeof(double)*16); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WHEEL_DISTANCE, (const char *)&packet, MAVLINK_MSG_ID_WHEEL_DISTANCE_MIN_LEN, MAVLINK_MSG_ID_WHEEL_DISTANCE_LEN, MAVLINK_MSG_ID_WHEEL_DISTANCE_CRC); -#endif -} - -/** - * @brief Send a wheel_distance message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_wheel_distance_send_struct(mavlink_channel_t chan, const mavlink_wheel_distance_t* wheel_distance) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_wheel_distance_send(chan, wheel_distance->time_usec, wheel_distance->count, wheel_distance->distance); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WHEEL_DISTANCE, (const char *)wheel_distance, MAVLINK_MSG_ID_WHEEL_DISTANCE_MIN_LEN, MAVLINK_MSG_ID_WHEEL_DISTANCE_LEN, MAVLINK_MSG_ID_WHEEL_DISTANCE_CRC); -#endif -} - -#if MAVLINK_MSG_ID_WHEEL_DISTANCE_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_wheel_distance_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, uint8_t count, const double *distance) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint8_t(buf, 136, count); - _mav_put_double_array(buf, 8, distance, 16); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WHEEL_DISTANCE, buf, MAVLINK_MSG_ID_WHEEL_DISTANCE_MIN_LEN, MAVLINK_MSG_ID_WHEEL_DISTANCE_LEN, MAVLINK_MSG_ID_WHEEL_DISTANCE_CRC); -#else - mavlink_wheel_distance_t *packet = (mavlink_wheel_distance_t *)msgbuf; - packet->time_usec = time_usec; - packet->count = count; - mav_array_memcpy(packet->distance, distance, sizeof(double)*16); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WHEEL_DISTANCE, (const char *)packet, MAVLINK_MSG_ID_WHEEL_DISTANCE_MIN_LEN, MAVLINK_MSG_ID_WHEEL_DISTANCE_LEN, MAVLINK_MSG_ID_WHEEL_DISTANCE_CRC); -#endif -} -#endif - -#endif - -// MESSAGE WHEEL_DISTANCE UNPACKING - - -/** - * @brief Get field time_usec from wheel_distance message - * - * @return [us] Timestamp (synced to UNIX time or since system boot). - */ -static inline uint64_t mavlink_msg_wheel_distance_get_time_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field count from wheel_distance message - * - * @return Number of wheels reported. - */ -static inline uint8_t mavlink_msg_wheel_distance_get_count(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 136); -} - -/** - * @brief Get field distance from wheel_distance message - * - * @return [m] Distance reported by individual wheel encoders. Forward rotations increase values, reverse rotations decrease them. Not all wheels will necessarily have wheel encoders; the mapping of encoders to wheel positions must be agreed/understood by the endpoints. - */ -static inline uint16_t mavlink_msg_wheel_distance_get_distance(const mavlink_message_t* msg, double *distance) -{ - return _MAV_RETURN_double_array(msg, distance, 16, 8); -} - -/** - * @brief Decode a wheel_distance message into a struct - * - * @param msg The message to decode - * @param wheel_distance C-struct to decode the message contents into - */ -static inline void mavlink_msg_wheel_distance_decode(const mavlink_message_t* msg, mavlink_wheel_distance_t* wheel_distance) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - wheel_distance->time_usec = mavlink_msg_wheel_distance_get_time_usec(msg); - mavlink_msg_wheel_distance_get_distance(msg, wheel_distance->distance); - wheel_distance->count = mavlink_msg_wheel_distance_get_count(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_WHEEL_DISTANCE_LEN? msg->len : MAVLINK_MSG_ID_WHEEL_DISTANCE_LEN; - memset(wheel_distance, 0, MAVLINK_MSG_ID_WHEEL_DISTANCE_LEN); - memcpy(wheel_distance, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_wifi_config_ap.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_wifi_config_ap.h deleted file mode 100644 index 743452d0..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_wifi_config_ap.h +++ /dev/null @@ -1,281 +0,0 @@ -#pragma once -// MESSAGE WIFI_CONFIG_AP PACKING - -#define MAVLINK_MSG_ID_WIFI_CONFIG_AP 299 - - -typedef struct __mavlink_wifi_config_ap_t { - char ssid[32]; /*< Name of Wi-Fi network (SSID). Blank to leave it unchanged when setting. Current SSID when sent back as a response.*/ - char password[64]; /*< Password. Blank for an open AP. MD5 hash when message is sent back as a response.*/ - int8_t mode; /*< WiFi Mode.*/ - int8_t response; /*< Message acceptance response (sent back to GS).*/ -} mavlink_wifi_config_ap_t; - -#define MAVLINK_MSG_ID_WIFI_CONFIG_AP_LEN 98 -#define MAVLINK_MSG_ID_WIFI_CONFIG_AP_MIN_LEN 96 -#define MAVLINK_MSG_ID_299_LEN 98 -#define MAVLINK_MSG_ID_299_MIN_LEN 96 - -#define MAVLINK_MSG_ID_WIFI_CONFIG_AP_CRC 19 -#define MAVLINK_MSG_ID_299_CRC 19 - -#define MAVLINK_MSG_WIFI_CONFIG_AP_FIELD_SSID_LEN 32 -#define MAVLINK_MSG_WIFI_CONFIG_AP_FIELD_PASSWORD_LEN 64 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_WIFI_CONFIG_AP { \ - 299, \ - "WIFI_CONFIG_AP", \ - 4, \ - { { "ssid", NULL, MAVLINK_TYPE_CHAR, 32, 0, offsetof(mavlink_wifi_config_ap_t, ssid) }, \ - { "password", NULL, MAVLINK_TYPE_CHAR, 64, 32, offsetof(mavlink_wifi_config_ap_t, password) }, \ - { "mode", NULL, MAVLINK_TYPE_INT8_T, 0, 96, offsetof(mavlink_wifi_config_ap_t, mode) }, \ - { "response", NULL, MAVLINK_TYPE_INT8_T, 0, 97, offsetof(mavlink_wifi_config_ap_t, response) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_WIFI_CONFIG_AP { \ - "WIFI_CONFIG_AP", \ - 4, \ - { { "ssid", NULL, MAVLINK_TYPE_CHAR, 32, 0, offsetof(mavlink_wifi_config_ap_t, ssid) }, \ - { "password", NULL, MAVLINK_TYPE_CHAR, 64, 32, offsetof(mavlink_wifi_config_ap_t, password) }, \ - { "mode", NULL, MAVLINK_TYPE_INT8_T, 0, 96, offsetof(mavlink_wifi_config_ap_t, mode) }, \ - { "response", NULL, MAVLINK_TYPE_INT8_T, 0, 97, offsetof(mavlink_wifi_config_ap_t, response) }, \ - } \ -} -#endif - -/** - * @brief Pack a wifi_config_ap message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param ssid Name of Wi-Fi network (SSID). Blank to leave it unchanged when setting. Current SSID when sent back as a response. - * @param password Password. Blank for an open AP. MD5 hash when message is sent back as a response. - * @param mode WiFi Mode. - * @param response Message acceptance response (sent back to GS). - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_wifi_config_ap_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - const char *ssid, const char *password, int8_t mode, int8_t response) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_WIFI_CONFIG_AP_LEN]; - _mav_put_int8_t(buf, 96, mode); - _mav_put_int8_t(buf, 97, response); - _mav_put_char_array(buf, 0, ssid, 32); - _mav_put_char_array(buf, 32, password, 64); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_WIFI_CONFIG_AP_LEN); -#else - mavlink_wifi_config_ap_t packet; - packet.mode = mode; - packet.response = response; - mav_array_memcpy(packet.ssid, ssid, sizeof(char)*32); - mav_array_memcpy(packet.password, password, sizeof(char)*64); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_WIFI_CONFIG_AP_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_WIFI_CONFIG_AP; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_WIFI_CONFIG_AP_MIN_LEN, MAVLINK_MSG_ID_WIFI_CONFIG_AP_LEN, MAVLINK_MSG_ID_WIFI_CONFIG_AP_CRC); -} - -/** - * @brief Pack a wifi_config_ap message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param ssid Name of Wi-Fi network (SSID). Blank to leave it unchanged when setting. Current SSID when sent back as a response. - * @param password Password. Blank for an open AP. MD5 hash when message is sent back as a response. - * @param mode WiFi Mode. - * @param response Message acceptance response (sent back to GS). - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_wifi_config_ap_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - const char *ssid,const char *password,int8_t mode,int8_t response) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_WIFI_CONFIG_AP_LEN]; - _mav_put_int8_t(buf, 96, mode); - _mav_put_int8_t(buf, 97, response); - _mav_put_char_array(buf, 0, ssid, 32); - _mav_put_char_array(buf, 32, password, 64); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_WIFI_CONFIG_AP_LEN); -#else - mavlink_wifi_config_ap_t packet; - packet.mode = mode; - packet.response = response; - mav_array_memcpy(packet.ssid, ssid, sizeof(char)*32); - mav_array_memcpy(packet.password, password, sizeof(char)*64); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_WIFI_CONFIG_AP_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_WIFI_CONFIG_AP; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_WIFI_CONFIG_AP_MIN_LEN, MAVLINK_MSG_ID_WIFI_CONFIG_AP_LEN, MAVLINK_MSG_ID_WIFI_CONFIG_AP_CRC); -} - -/** - * @brief Encode a wifi_config_ap struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param wifi_config_ap C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_wifi_config_ap_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_wifi_config_ap_t* wifi_config_ap) -{ - return mavlink_msg_wifi_config_ap_pack(system_id, component_id, msg, wifi_config_ap->ssid, wifi_config_ap->password, wifi_config_ap->mode, wifi_config_ap->response); -} - -/** - * @brief Encode a wifi_config_ap struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param wifi_config_ap C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_wifi_config_ap_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_wifi_config_ap_t* wifi_config_ap) -{ - return mavlink_msg_wifi_config_ap_pack_chan(system_id, component_id, chan, msg, wifi_config_ap->ssid, wifi_config_ap->password, wifi_config_ap->mode, wifi_config_ap->response); -} - -/** - * @brief Send a wifi_config_ap message - * @param chan MAVLink channel to send the message - * - * @param ssid Name of Wi-Fi network (SSID). Blank to leave it unchanged when setting. Current SSID when sent back as a response. - * @param password Password. Blank for an open AP. MD5 hash when message is sent back as a response. - * @param mode WiFi Mode. - * @param response Message acceptance response (sent back to GS). - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_wifi_config_ap_send(mavlink_channel_t chan, const char *ssid, const char *password, int8_t mode, int8_t response) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_WIFI_CONFIG_AP_LEN]; - _mav_put_int8_t(buf, 96, mode); - _mav_put_int8_t(buf, 97, response); - _mav_put_char_array(buf, 0, ssid, 32); - _mav_put_char_array(buf, 32, password, 64); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WIFI_CONFIG_AP, buf, MAVLINK_MSG_ID_WIFI_CONFIG_AP_MIN_LEN, MAVLINK_MSG_ID_WIFI_CONFIG_AP_LEN, MAVLINK_MSG_ID_WIFI_CONFIG_AP_CRC); -#else - mavlink_wifi_config_ap_t packet; - packet.mode = mode; - packet.response = response; - mav_array_memcpy(packet.ssid, ssid, sizeof(char)*32); - mav_array_memcpy(packet.password, password, sizeof(char)*64); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WIFI_CONFIG_AP, (const char *)&packet, MAVLINK_MSG_ID_WIFI_CONFIG_AP_MIN_LEN, MAVLINK_MSG_ID_WIFI_CONFIG_AP_LEN, MAVLINK_MSG_ID_WIFI_CONFIG_AP_CRC); -#endif -} - -/** - * @brief Send a wifi_config_ap message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_wifi_config_ap_send_struct(mavlink_channel_t chan, const mavlink_wifi_config_ap_t* wifi_config_ap) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_wifi_config_ap_send(chan, wifi_config_ap->ssid, wifi_config_ap->password, wifi_config_ap->mode, wifi_config_ap->response); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WIFI_CONFIG_AP, (const char *)wifi_config_ap, MAVLINK_MSG_ID_WIFI_CONFIG_AP_MIN_LEN, MAVLINK_MSG_ID_WIFI_CONFIG_AP_LEN, MAVLINK_MSG_ID_WIFI_CONFIG_AP_CRC); -#endif -} - -#if MAVLINK_MSG_ID_WIFI_CONFIG_AP_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_wifi_config_ap_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, const char *ssid, const char *password, int8_t mode, int8_t response) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_int8_t(buf, 96, mode); - _mav_put_int8_t(buf, 97, response); - _mav_put_char_array(buf, 0, ssid, 32); - _mav_put_char_array(buf, 32, password, 64); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WIFI_CONFIG_AP, buf, MAVLINK_MSG_ID_WIFI_CONFIG_AP_MIN_LEN, MAVLINK_MSG_ID_WIFI_CONFIG_AP_LEN, MAVLINK_MSG_ID_WIFI_CONFIG_AP_CRC); -#else - mavlink_wifi_config_ap_t *packet = (mavlink_wifi_config_ap_t *)msgbuf; - packet->mode = mode; - packet->response = response; - mav_array_memcpy(packet->ssid, ssid, sizeof(char)*32); - mav_array_memcpy(packet->password, password, sizeof(char)*64); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WIFI_CONFIG_AP, (const char *)packet, MAVLINK_MSG_ID_WIFI_CONFIG_AP_MIN_LEN, MAVLINK_MSG_ID_WIFI_CONFIG_AP_LEN, MAVLINK_MSG_ID_WIFI_CONFIG_AP_CRC); -#endif -} -#endif - -#endif - -// MESSAGE WIFI_CONFIG_AP UNPACKING - - -/** - * @brief Get field ssid from wifi_config_ap message - * - * @return Name of Wi-Fi network (SSID). Blank to leave it unchanged when setting. Current SSID when sent back as a response. - */ -static inline uint16_t mavlink_msg_wifi_config_ap_get_ssid(const mavlink_message_t* msg, char *ssid) -{ - return _MAV_RETURN_char_array(msg, ssid, 32, 0); -} - -/** - * @brief Get field password from wifi_config_ap message - * - * @return Password. Blank for an open AP. MD5 hash when message is sent back as a response. - */ -static inline uint16_t mavlink_msg_wifi_config_ap_get_password(const mavlink_message_t* msg, char *password) -{ - return _MAV_RETURN_char_array(msg, password, 64, 32); -} - -/** - * @brief Get field mode from wifi_config_ap message - * - * @return WiFi Mode. - */ -static inline int8_t mavlink_msg_wifi_config_ap_get_mode(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int8_t(msg, 96); -} - -/** - * @brief Get field response from wifi_config_ap message - * - * @return Message acceptance response (sent back to GS). - */ -static inline int8_t mavlink_msg_wifi_config_ap_get_response(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int8_t(msg, 97); -} - -/** - * @brief Decode a wifi_config_ap message into a struct - * - * @param msg The message to decode - * @param wifi_config_ap C-struct to decode the message contents into - */ -static inline void mavlink_msg_wifi_config_ap_decode(const mavlink_message_t* msg, mavlink_wifi_config_ap_t* wifi_config_ap) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_wifi_config_ap_get_ssid(msg, wifi_config_ap->ssid); - mavlink_msg_wifi_config_ap_get_password(msg, wifi_config_ap->password); - wifi_config_ap->mode = mavlink_msg_wifi_config_ap_get_mode(msg); - wifi_config_ap->response = mavlink_msg_wifi_config_ap_get_response(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_WIFI_CONFIG_AP_LEN? msg->len : MAVLINK_MSG_ID_WIFI_CONFIG_AP_LEN; - memset(wifi_config_ap, 0, MAVLINK_MSG_ID_WIFI_CONFIG_AP_LEN); - memcpy(wifi_config_ap, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_winch_status.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_winch_status.h deleted file mode 100644 index d164007c..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_winch_status.h +++ /dev/null @@ -1,388 +0,0 @@ -#pragma once -// MESSAGE WINCH_STATUS PACKING - -#define MAVLINK_MSG_ID_WINCH_STATUS 9005 - - -typedef struct __mavlink_winch_status_t { - uint64_t time_usec; /*< [us] Timestamp (synced to UNIX time or since system boot).*/ - float line_length; /*< [m] Length of line released. NaN if unknown*/ - float speed; /*< [m/s] Speed line is being released or retracted. Positive values if being released, negative values if being retracted, NaN if unknown*/ - float tension; /*< [kg] Tension on the line. NaN if unknown*/ - float voltage; /*< [V] Voltage of the battery supplying the winch. NaN if unknown*/ - float current; /*< [A] Current draw from the winch. NaN if unknown*/ - uint32_t status; /*< Status flags*/ - int16_t temperature; /*< [degC] Temperature of the motor. INT16_MAX if unknown*/ -} mavlink_winch_status_t; - -#define MAVLINK_MSG_ID_WINCH_STATUS_LEN 34 -#define MAVLINK_MSG_ID_WINCH_STATUS_MIN_LEN 34 -#define MAVLINK_MSG_ID_9005_LEN 34 -#define MAVLINK_MSG_ID_9005_MIN_LEN 34 - -#define MAVLINK_MSG_ID_WINCH_STATUS_CRC 117 -#define MAVLINK_MSG_ID_9005_CRC 117 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_WINCH_STATUS { \ - 9005, \ - "WINCH_STATUS", \ - 8, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_winch_status_t, time_usec) }, \ - { "line_length", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_winch_status_t, line_length) }, \ - { "speed", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_winch_status_t, speed) }, \ - { "tension", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_winch_status_t, tension) }, \ - { "voltage", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_winch_status_t, voltage) }, \ - { "current", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_winch_status_t, current) }, \ - { "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 32, offsetof(mavlink_winch_status_t, temperature) }, \ - { "status", NULL, MAVLINK_TYPE_UINT32_T, 0, 28, offsetof(mavlink_winch_status_t, status) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_WINCH_STATUS { \ - "WINCH_STATUS", \ - 8, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_winch_status_t, time_usec) }, \ - { "line_length", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_winch_status_t, line_length) }, \ - { "speed", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_winch_status_t, speed) }, \ - { "tension", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_winch_status_t, tension) }, \ - { "voltage", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_winch_status_t, voltage) }, \ - { "current", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_winch_status_t, current) }, \ - { "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 32, offsetof(mavlink_winch_status_t, temperature) }, \ - { "status", NULL, MAVLINK_TYPE_UINT32_T, 0, 28, offsetof(mavlink_winch_status_t, status) }, \ - } \ -} -#endif - -/** - * @brief Pack a winch_status message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param time_usec [us] Timestamp (synced to UNIX time or since system boot). - * @param line_length [m] Length of line released. NaN if unknown - * @param speed [m/s] Speed line is being released or retracted. Positive values if being released, negative values if being retracted, NaN if unknown - * @param tension [kg] Tension on the line. NaN if unknown - * @param voltage [V] Voltage of the battery supplying the winch. NaN if unknown - * @param current [A] Current draw from the winch. NaN if unknown - * @param temperature [degC] Temperature of the motor. INT16_MAX if unknown - * @param status Status flags - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_winch_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint64_t time_usec, float line_length, float speed, float tension, float voltage, float current, int16_t temperature, uint32_t status) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_WINCH_STATUS_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, line_length); - _mav_put_float(buf, 12, speed); - _mav_put_float(buf, 16, tension); - _mav_put_float(buf, 20, voltage); - _mav_put_float(buf, 24, current); - _mav_put_uint32_t(buf, 28, status); - _mav_put_int16_t(buf, 32, temperature); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_WINCH_STATUS_LEN); -#else - mavlink_winch_status_t packet; - packet.time_usec = time_usec; - packet.line_length = line_length; - packet.speed = speed; - packet.tension = tension; - packet.voltage = voltage; - packet.current = current; - packet.status = status; - packet.temperature = temperature; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_WINCH_STATUS_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_WINCH_STATUS; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_WINCH_STATUS_MIN_LEN, MAVLINK_MSG_ID_WINCH_STATUS_LEN, MAVLINK_MSG_ID_WINCH_STATUS_CRC); -} - -/** - * @brief Pack a winch_status message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_usec [us] Timestamp (synced to UNIX time or since system boot). - * @param line_length [m] Length of line released. NaN if unknown - * @param speed [m/s] Speed line is being released or retracted. Positive values if being released, negative values if being retracted, NaN if unknown - * @param tension [kg] Tension on the line. NaN if unknown - * @param voltage [V] Voltage of the battery supplying the winch. NaN if unknown - * @param current [A] Current draw from the winch. NaN if unknown - * @param temperature [degC] Temperature of the motor. INT16_MAX if unknown - * @param status Status flags - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_winch_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint64_t time_usec,float line_length,float speed,float tension,float voltage,float current,int16_t temperature,uint32_t status) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_WINCH_STATUS_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, line_length); - _mav_put_float(buf, 12, speed); - _mav_put_float(buf, 16, tension); - _mav_put_float(buf, 20, voltage); - _mav_put_float(buf, 24, current); - _mav_put_uint32_t(buf, 28, status); - _mav_put_int16_t(buf, 32, temperature); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_WINCH_STATUS_LEN); -#else - mavlink_winch_status_t packet; - packet.time_usec = time_usec; - packet.line_length = line_length; - packet.speed = speed; - packet.tension = tension; - packet.voltage = voltage; - packet.current = current; - packet.status = status; - packet.temperature = temperature; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_WINCH_STATUS_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_WINCH_STATUS; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_WINCH_STATUS_MIN_LEN, MAVLINK_MSG_ID_WINCH_STATUS_LEN, MAVLINK_MSG_ID_WINCH_STATUS_CRC); -} - -/** - * @brief Encode a winch_status struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param winch_status C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_winch_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_winch_status_t* winch_status) -{ - return mavlink_msg_winch_status_pack(system_id, component_id, msg, winch_status->time_usec, winch_status->line_length, winch_status->speed, winch_status->tension, winch_status->voltage, winch_status->current, winch_status->temperature, winch_status->status); -} - -/** - * @brief Encode a winch_status struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param winch_status C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_winch_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_winch_status_t* winch_status) -{ - return mavlink_msg_winch_status_pack_chan(system_id, component_id, chan, msg, winch_status->time_usec, winch_status->line_length, winch_status->speed, winch_status->tension, winch_status->voltage, winch_status->current, winch_status->temperature, winch_status->status); -} - -/** - * @brief Send a winch_status message - * @param chan MAVLink channel to send the message - * - * @param time_usec [us] Timestamp (synced to UNIX time or since system boot). - * @param line_length [m] Length of line released. NaN if unknown - * @param speed [m/s] Speed line is being released or retracted. Positive values if being released, negative values if being retracted, NaN if unknown - * @param tension [kg] Tension on the line. NaN if unknown - * @param voltage [V] Voltage of the battery supplying the winch. NaN if unknown - * @param current [A] Current draw from the winch. NaN if unknown - * @param temperature [degC] Temperature of the motor. INT16_MAX if unknown - * @param status Status flags - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_winch_status_send(mavlink_channel_t chan, uint64_t time_usec, float line_length, float speed, float tension, float voltage, float current, int16_t temperature, uint32_t status) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_WINCH_STATUS_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, line_length); - _mav_put_float(buf, 12, speed); - _mav_put_float(buf, 16, tension); - _mav_put_float(buf, 20, voltage); - _mav_put_float(buf, 24, current); - _mav_put_uint32_t(buf, 28, status); - _mav_put_int16_t(buf, 32, temperature); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WINCH_STATUS, buf, MAVLINK_MSG_ID_WINCH_STATUS_MIN_LEN, MAVLINK_MSG_ID_WINCH_STATUS_LEN, MAVLINK_MSG_ID_WINCH_STATUS_CRC); -#else - mavlink_winch_status_t packet; - packet.time_usec = time_usec; - packet.line_length = line_length; - packet.speed = speed; - packet.tension = tension; - packet.voltage = voltage; - packet.current = current; - packet.status = status; - packet.temperature = temperature; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WINCH_STATUS, (const char *)&packet, MAVLINK_MSG_ID_WINCH_STATUS_MIN_LEN, MAVLINK_MSG_ID_WINCH_STATUS_LEN, MAVLINK_MSG_ID_WINCH_STATUS_CRC); -#endif -} - -/** - * @brief Send a winch_status message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_winch_status_send_struct(mavlink_channel_t chan, const mavlink_winch_status_t* winch_status) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_winch_status_send(chan, winch_status->time_usec, winch_status->line_length, winch_status->speed, winch_status->tension, winch_status->voltage, winch_status->current, winch_status->temperature, winch_status->status); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WINCH_STATUS, (const char *)winch_status, MAVLINK_MSG_ID_WINCH_STATUS_MIN_LEN, MAVLINK_MSG_ID_WINCH_STATUS_LEN, MAVLINK_MSG_ID_WINCH_STATUS_CRC); -#endif -} - -#if MAVLINK_MSG_ID_WINCH_STATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_winch_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, float line_length, float speed, float tension, float voltage, float current, int16_t temperature, uint32_t status) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, line_length); - _mav_put_float(buf, 12, speed); - _mav_put_float(buf, 16, tension); - _mav_put_float(buf, 20, voltage); - _mav_put_float(buf, 24, current); - _mav_put_uint32_t(buf, 28, status); - _mav_put_int16_t(buf, 32, temperature); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WINCH_STATUS, buf, MAVLINK_MSG_ID_WINCH_STATUS_MIN_LEN, MAVLINK_MSG_ID_WINCH_STATUS_LEN, MAVLINK_MSG_ID_WINCH_STATUS_CRC); -#else - mavlink_winch_status_t *packet = (mavlink_winch_status_t *)msgbuf; - packet->time_usec = time_usec; - packet->line_length = line_length; - packet->speed = speed; - packet->tension = tension; - packet->voltage = voltage; - packet->current = current; - packet->status = status; - packet->temperature = temperature; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WINCH_STATUS, (const char *)packet, MAVLINK_MSG_ID_WINCH_STATUS_MIN_LEN, MAVLINK_MSG_ID_WINCH_STATUS_LEN, MAVLINK_MSG_ID_WINCH_STATUS_CRC); -#endif -} -#endif - -#endif - -// MESSAGE WINCH_STATUS UNPACKING - - -/** - * @brief Get field time_usec from winch_status message - * - * @return [us] Timestamp (synced to UNIX time or since system boot). - */ -static inline uint64_t mavlink_msg_winch_status_get_time_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field line_length from winch_status message - * - * @return [m] Length of line released. NaN if unknown - */ -static inline float mavlink_msg_winch_status_get_line_length(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field speed from winch_status message - * - * @return [m/s] Speed line is being released or retracted. Positive values if being released, negative values if being retracted, NaN if unknown - */ -static inline float mavlink_msg_winch_status_get_speed(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field tension from winch_status message - * - * @return [kg] Tension on the line. NaN if unknown - */ -static inline float mavlink_msg_winch_status_get_tension(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field voltage from winch_status message - * - * @return [V] Voltage of the battery supplying the winch. NaN if unknown - */ -static inline float mavlink_msg_winch_status_get_voltage(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Get field current from winch_status message - * - * @return [A] Current draw from the winch. NaN if unknown - */ -static inline float mavlink_msg_winch_status_get_current(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Get field temperature from winch_status message - * - * @return [degC] Temperature of the motor. INT16_MAX if unknown - */ -static inline int16_t mavlink_msg_winch_status_get_temperature(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 32); -} - -/** - * @brief Get field status from winch_status message - * - * @return Status flags - */ -static inline uint32_t mavlink_msg_winch_status_get_status(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 28); -} - -/** - * @brief Decode a winch_status message into a struct - * - * @param msg The message to decode - * @param winch_status C-struct to decode the message contents into - */ -static inline void mavlink_msg_winch_status_decode(const mavlink_message_t* msg, mavlink_winch_status_t* winch_status) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - winch_status->time_usec = mavlink_msg_winch_status_get_time_usec(msg); - winch_status->line_length = mavlink_msg_winch_status_get_line_length(msg); - winch_status->speed = mavlink_msg_winch_status_get_speed(msg); - winch_status->tension = mavlink_msg_winch_status_get_tension(msg); - winch_status->voltage = mavlink_msg_winch_status_get_voltage(msg); - winch_status->current = mavlink_msg_winch_status_get_current(msg); - winch_status->status = mavlink_msg_winch_status_get_status(msg); - winch_status->temperature = mavlink_msg_winch_status_get_temperature(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_WINCH_STATUS_LEN? msg->len : MAVLINK_MSG_ID_WINCH_STATUS_LEN; - memset(winch_status, 0, MAVLINK_MSG_ID_WINCH_STATUS_LEN); - memcpy(winch_status, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_wind_cov.h b/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_wind_cov.h deleted file mode 100644 index 27c0d18e..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/mavlink_msg_wind_cov.h +++ /dev/null @@ -1,413 +0,0 @@ -#pragma once -// MESSAGE WIND_COV PACKING - -#define MAVLINK_MSG_ID_WIND_COV 231 - - -typedef struct __mavlink_wind_cov_t { - uint64_t time_usec; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/ - float wind_x; /*< [m/s] Wind in North (NED) direction (NAN if unknown)*/ - float wind_y; /*< [m/s] Wind in East (NED) direction (NAN if unknown)*/ - float wind_z; /*< [m/s] Wind in down (NED) direction (NAN if unknown)*/ - float var_horiz; /*< [m/s] Variability of wind in XY, 1-STD estimated from a 1 Hz lowpassed wind estimate (NAN if unknown)*/ - float var_vert; /*< [m/s] Variability of wind in Z, 1-STD estimated from a 1 Hz lowpassed wind estimate (NAN if unknown)*/ - float wind_alt; /*< [m] Altitude (MSL) that this measurement was taken at (NAN if unknown)*/ - float horiz_accuracy; /*< [m/s] Horizontal speed 1-STD accuracy (0 if unknown)*/ - float vert_accuracy; /*< [m/s] Vertical speed 1-STD accuracy (0 if unknown)*/ -} mavlink_wind_cov_t; - -#define MAVLINK_MSG_ID_WIND_COV_LEN 40 -#define MAVLINK_MSG_ID_WIND_COV_MIN_LEN 40 -#define MAVLINK_MSG_ID_231_LEN 40 -#define MAVLINK_MSG_ID_231_MIN_LEN 40 - -#define MAVLINK_MSG_ID_WIND_COV_CRC 105 -#define MAVLINK_MSG_ID_231_CRC 105 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_WIND_COV { \ - 231, \ - "WIND_COV", \ - 9, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_wind_cov_t, time_usec) }, \ - { "wind_x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_wind_cov_t, wind_x) }, \ - { "wind_y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_wind_cov_t, wind_y) }, \ - { "wind_z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_wind_cov_t, wind_z) }, \ - { "var_horiz", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_wind_cov_t, var_horiz) }, \ - { "var_vert", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_wind_cov_t, var_vert) }, \ - { "wind_alt", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_wind_cov_t, wind_alt) }, \ - { "horiz_accuracy", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_wind_cov_t, horiz_accuracy) }, \ - { "vert_accuracy", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_wind_cov_t, vert_accuracy) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_WIND_COV { \ - "WIND_COV", \ - 9, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_wind_cov_t, time_usec) }, \ - { "wind_x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_wind_cov_t, wind_x) }, \ - { "wind_y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_wind_cov_t, wind_y) }, \ - { "wind_z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_wind_cov_t, wind_z) }, \ - { "var_horiz", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_wind_cov_t, var_horiz) }, \ - { "var_vert", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_wind_cov_t, var_vert) }, \ - { "wind_alt", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_wind_cov_t, wind_alt) }, \ - { "horiz_accuracy", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_wind_cov_t, horiz_accuracy) }, \ - { "vert_accuracy", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_wind_cov_t, vert_accuracy) }, \ - } \ -} -#endif - -/** - * @brief Pack a wind_cov message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @param wind_x [m/s] Wind in North (NED) direction (NAN if unknown) - * @param wind_y [m/s] Wind in East (NED) direction (NAN if unknown) - * @param wind_z [m/s] Wind in down (NED) direction (NAN if unknown) - * @param var_horiz [m/s] Variability of wind in XY, 1-STD estimated from a 1 Hz lowpassed wind estimate (NAN if unknown) - * @param var_vert [m/s] Variability of wind in Z, 1-STD estimated from a 1 Hz lowpassed wind estimate (NAN if unknown) - * @param wind_alt [m] Altitude (MSL) that this measurement was taken at (NAN if unknown) - * @param horiz_accuracy [m/s] Horizontal speed 1-STD accuracy (0 if unknown) - * @param vert_accuracy [m/s] Vertical speed 1-STD accuracy (0 if unknown) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_wind_cov_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint64_t time_usec, float wind_x, float wind_y, float wind_z, float var_horiz, float var_vert, float wind_alt, float horiz_accuracy, float vert_accuracy) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_WIND_COV_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, wind_x); - _mav_put_float(buf, 12, wind_y); - _mav_put_float(buf, 16, wind_z); - _mav_put_float(buf, 20, var_horiz); - _mav_put_float(buf, 24, var_vert); - _mav_put_float(buf, 28, wind_alt); - _mav_put_float(buf, 32, horiz_accuracy); - _mav_put_float(buf, 36, vert_accuracy); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_WIND_COV_LEN); -#else - mavlink_wind_cov_t packet; - packet.time_usec = time_usec; - packet.wind_x = wind_x; - packet.wind_y = wind_y; - packet.wind_z = wind_z; - packet.var_horiz = var_horiz; - packet.var_vert = var_vert; - packet.wind_alt = wind_alt; - packet.horiz_accuracy = horiz_accuracy; - packet.vert_accuracy = vert_accuracy; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_WIND_COV_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_WIND_COV; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_WIND_COV_MIN_LEN, MAVLINK_MSG_ID_WIND_COV_LEN, MAVLINK_MSG_ID_WIND_COV_CRC); -} - -/** - * @brief Pack a wind_cov message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @param wind_x [m/s] Wind in North (NED) direction (NAN if unknown) - * @param wind_y [m/s] Wind in East (NED) direction (NAN if unknown) - * @param wind_z [m/s] Wind in down (NED) direction (NAN if unknown) - * @param var_horiz [m/s] Variability of wind in XY, 1-STD estimated from a 1 Hz lowpassed wind estimate (NAN if unknown) - * @param var_vert [m/s] Variability of wind in Z, 1-STD estimated from a 1 Hz lowpassed wind estimate (NAN if unknown) - * @param wind_alt [m] Altitude (MSL) that this measurement was taken at (NAN if unknown) - * @param horiz_accuracy [m/s] Horizontal speed 1-STD accuracy (0 if unknown) - * @param vert_accuracy [m/s] Vertical speed 1-STD accuracy (0 if unknown) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_wind_cov_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint64_t time_usec,float wind_x,float wind_y,float wind_z,float var_horiz,float var_vert,float wind_alt,float horiz_accuracy,float vert_accuracy) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_WIND_COV_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, wind_x); - _mav_put_float(buf, 12, wind_y); - _mav_put_float(buf, 16, wind_z); - _mav_put_float(buf, 20, var_horiz); - _mav_put_float(buf, 24, var_vert); - _mav_put_float(buf, 28, wind_alt); - _mav_put_float(buf, 32, horiz_accuracy); - _mav_put_float(buf, 36, vert_accuracy); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_WIND_COV_LEN); -#else - mavlink_wind_cov_t packet; - packet.time_usec = time_usec; - packet.wind_x = wind_x; - packet.wind_y = wind_y; - packet.wind_z = wind_z; - packet.var_horiz = var_horiz; - packet.var_vert = var_vert; - packet.wind_alt = wind_alt; - packet.horiz_accuracy = horiz_accuracy; - packet.vert_accuracy = vert_accuracy; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_WIND_COV_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_WIND_COV; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_WIND_COV_MIN_LEN, MAVLINK_MSG_ID_WIND_COV_LEN, MAVLINK_MSG_ID_WIND_COV_CRC); -} - -/** - * @brief Encode a wind_cov struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param wind_cov C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_wind_cov_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_wind_cov_t* wind_cov) -{ - return mavlink_msg_wind_cov_pack(system_id, component_id, msg, wind_cov->time_usec, wind_cov->wind_x, wind_cov->wind_y, wind_cov->wind_z, wind_cov->var_horiz, wind_cov->var_vert, wind_cov->wind_alt, wind_cov->horiz_accuracy, wind_cov->vert_accuracy); -} - -/** - * @brief Encode a wind_cov struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param wind_cov C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_wind_cov_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_wind_cov_t* wind_cov) -{ - return mavlink_msg_wind_cov_pack_chan(system_id, component_id, chan, msg, wind_cov->time_usec, wind_cov->wind_x, wind_cov->wind_y, wind_cov->wind_z, wind_cov->var_horiz, wind_cov->var_vert, wind_cov->wind_alt, wind_cov->horiz_accuracy, wind_cov->vert_accuracy); -} - -/** - * @brief Send a wind_cov message - * @param chan MAVLink channel to send the message - * - * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - * @param wind_x [m/s] Wind in North (NED) direction (NAN if unknown) - * @param wind_y [m/s] Wind in East (NED) direction (NAN if unknown) - * @param wind_z [m/s] Wind in down (NED) direction (NAN if unknown) - * @param var_horiz [m/s] Variability of wind in XY, 1-STD estimated from a 1 Hz lowpassed wind estimate (NAN if unknown) - * @param var_vert [m/s] Variability of wind in Z, 1-STD estimated from a 1 Hz lowpassed wind estimate (NAN if unknown) - * @param wind_alt [m] Altitude (MSL) that this measurement was taken at (NAN if unknown) - * @param horiz_accuracy [m/s] Horizontal speed 1-STD accuracy (0 if unknown) - * @param vert_accuracy [m/s] Vertical speed 1-STD accuracy (0 if unknown) - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_wind_cov_send(mavlink_channel_t chan, uint64_t time_usec, float wind_x, float wind_y, float wind_z, float var_horiz, float var_vert, float wind_alt, float horiz_accuracy, float vert_accuracy) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_WIND_COV_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, wind_x); - _mav_put_float(buf, 12, wind_y); - _mav_put_float(buf, 16, wind_z); - _mav_put_float(buf, 20, var_horiz); - _mav_put_float(buf, 24, var_vert); - _mav_put_float(buf, 28, wind_alt); - _mav_put_float(buf, 32, horiz_accuracy); - _mav_put_float(buf, 36, vert_accuracy); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WIND_COV, buf, MAVLINK_MSG_ID_WIND_COV_MIN_LEN, MAVLINK_MSG_ID_WIND_COV_LEN, MAVLINK_MSG_ID_WIND_COV_CRC); -#else - mavlink_wind_cov_t packet; - packet.time_usec = time_usec; - packet.wind_x = wind_x; - packet.wind_y = wind_y; - packet.wind_z = wind_z; - packet.var_horiz = var_horiz; - packet.var_vert = var_vert; - packet.wind_alt = wind_alt; - packet.horiz_accuracy = horiz_accuracy; - packet.vert_accuracy = vert_accuracy; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WIND_COV, (const char *)&packet, MAVLINK_MSG_ID_WIND_COV_MIN_LEN, MAVLINK_MSG_ID_WIND_COV_LEN, MAVLINK_MSG_ID_WIND_COV_CRC); -#endif -} - -/** - * @brief Send a wind_cov message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_wind_cov_send_struct(mavlink_channel_t chan, const mavlink_wind_cov_t* wind_cov) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_wind_cov_send(chan, wind_cov->time_usec, wind_cov->wind_x, wind_cov->wind_y, wind_cov->wind_z, wind_cov->var_horiz, wind_cov->var_vert, wind_cov->wind_alt, wind_cov->horiz_accuracy, wind_cov->vert_accuracy); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WIND_COV, (const char *)wind_cov, MAVLINK_MSG_ID_WIND_COV_MIN_LEN, MAVLINK_MSG_ID_WIND_COV_LEN, MAVLINK_MSG_ID_WIND_COV_CRC); -#endif -} - -#if MAVLINK_MSG_ID_WIND_COV_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_wind_cov_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, float wind_x, float wind_y, float wind_z, float var_horiz, float var_vert, float wind_alt, float horiz_accuracy, float vert_accuracy) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, wind_x); - _mav_put_float(buf, 12, wind_y); - _mav_put_float(buf, 16, wind_z); - _mav_put_float(buf, 20, var_horiz); - _mav_put_float(buf, 24, var_vert); - _mav_put_float(buf, 28, wind_alt); - _mav_put_float(buf, 32, horiz_accuracy); - _mav_put_float(buf, 36, vert_accuracy); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WIND_COV, buf, MAVLINK_MSG_ID_WIND_COV_MIN_LEN, MAVLINK_MSG_ID_WIND_COV_LEN, MAVLINK_MSG_ID_WIND_COV_CRC); -#else - mavlink_wind_cov_t *packet = (mavlink_wind_cov_t *)msgbuf; - packet->time_usec = time_usec; - packet->wind_x = wind_x; - packet->wind_y = wind_y; - packet->wind_z = wind_z; - packet->var_horiz = var_horiz; - packet->var_vert = var_vert; - packet->wind_alt = wind_alt; - packet->horiz_accuracy = horiz_accuracy; - packet->vert_accuracy = vert_accuracy; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WIND_COV, (const char *)packet, MAVLINK_MSG_ID_WIND_COV_MIN_LEN, MAVLINK_MSG_ID_WIND_COV_LEN, MAVLINK_MSG_ID_WIND_COV_CRC); -#endif -} -#endif - -#endif - -// MESSAGE WIND_COV UNPACKING - - -/** - * @brief Get field time_usec from wind_cov message - * - * @return [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - */ -static inline uint64_t mavlink_msg_wind_cov_get_time_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field wind_x from wind_cov message - * - * @return [m/s] Wind in North (NED) direction (NAN if unknown) - */ -static inline float mavlink_msg_wind_cov_get_wind_x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field wind_y from wind_cov message - * - * @return [m/s] Wind in East (NED) direction (NAN if unknown) - */ -static inline float mavlink_msg_wind_cov_get_wind_y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field wind_z from wind_cov message - * - * @return [m/s] Wind in down (NED) direction (NAN if unknown) - */ -static inline float mavlink_msg_wind_cov_get_wind_z(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field var_horiz from wind_cov message - * - * @return [m/s] Variability of wind in XY, 1-STD estimated from a 1 Hz lowpassed wind estimate (NAN if unknown) - */ -static inline float mavlink_msg_wind_cov_get_var_horiz(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Get field var_vert from wind_cov message - * - * @return [m/s] Variability of wind in Z, 1-STD estimated from a 1 Hz lowpassed wind estimate (NAN if unknown) - */ -static inline float mavlink_msg_wind_cov_get_var_vert(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Get field wind_alt from wind_cov message - * - * @return [m] Altitude (MSL) that this measurement was taken at (NAN if unknown) - */ -static inline float mavlink_msg_wind_cov_get_wind_alt(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 28); -} - -/** - * @brief Get field horiz_accuracy from wind_cov message - * - * @return [m/s] Horizontal speed 1-STD accuracy (0 if unknown) - */ -static inline float mavlink_msg_wind_cov_get_horiz_accuracy(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 32); -} - -/** - * @brief Get field vert_accuracy from wind_cov message - * - * @return [m/s] Vertical speed 1-STD accuracy (0 if unknown) - */ -static inline float mavlink_msg_wind_cov_get_vert_accuracy(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 36); -} - -/** - * @brief Decode a wind_cov message into a struct - * - * @param msg The message to decode - * @param wind_cov C-struct to decode the message contents into - */ -static inline void mavlink_msg_wind_cov_decode(const mavlink_message_t* msg, mavlink_wind_cov_t* wind_cov) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - wind_cov->time_usec = mavlink_msg_wind_cov_get_time_usec(msg); - wind_cov->wind_x = mavlink_msg_wind_cov_get_wind_x(msg); - wind_cov->wind_y = mavlink_msg_wind_cov_get_wind_y(msg); - wind_cov->wind_z = mavlink_msg_wind_cov_get_wind_z(msg); - wind_cov->var_horiz = mavlink_msg_wind_cov_get_var_horiz(msg); - wind_cov->var_vert = mavlink_msg_wind_cov_get_var_vert(msg); - wind_cov->wind_alt = mavlink_msg_wind_cov_get_wind_alt(msg); - wind_cov->horiz_accuracy = mavlink_msg_wind_cov_get_horiz_accuracy(msg); - wind_cov->vert_accuracy = mavlink_msg_wind_cov_get_vert_accuracy(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_WIND_COV_LEN? msg->len : MAVLINK_MSG_ID_WIND_COV_LEN; - memset(wind_cov, 0, MAVLINK_MSG_ID_WIND_COV_LEN); - memcpy(wind_cov, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/common/testsuite.h b/TelemetryManager/Inc/official_mavlink_2_library/common/testsuite.h deleted file mode 100644 index 95d5ca4b..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/common/testsuite.h +++ /dev/null @@ -1,14741 +0,0 @@ -/** @file - * @brief MAVLink comm protocol testsuite generated from common.xml - * @see https://mavlink.io/en/ - */ -#pragma once -#ifndef COMMON_TESTSUITE_H -#define COMMON_TESTSUITE_H - -#ifdef __cplusplus -extern "C" { -#endif - -#ifndef MAVLINK_TEST_ALL -#define MAVLINK_TEST_ALL -static void mavlink_test_standard(uint8_t, uint8_t, mavlink_message_t *last_msg); -static void mavlink_test_common(uint8_t, uint8_t, mavlink_message_t *last_msg); - -static void mavlink_test_all(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg) -{ - mavlink_test_standard(system_id, component_id, last_msg); - mavlink_test_common(system_id, component_id, last_msg); -} -#endif - -#include "../standard/testsuite.h" - - -static void mavlink_test_sys_status(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg) -{ -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - mavlink_status_t *status = mavlink_get_channel_status(MAVLINK_COMM_0); - if ((status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_SYS_STATUS >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_sys_status_t packet_in = { - 963497464,963497672,963497880,17859,17963,18067,18171,18275,18379,18483,18587,18691,223,963499076,963499284,963499492 - }; - mavlink_sys_status_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.onboard_control_sensors_present = packet_in.onboard_control_sensors_present; - packet1.onboard_control_sensors_enabled = packet_in.onboard_control_sensors_enabled; - packet1.onboard_control_sensors_health = packet_in.onboard_control_sensors_health; - packet1.load = packet_in.load; - packet1.voltage_battery = packet_in.voltage_battery; - packet1.current_battery = packet_in.current_battery; - packet1.drop_rate_comm = packet_in.drop_rate_comm; - packet1.errors_comm = packet_in.errors_comm; - packet1.errors_count1 = packet_in.errors_count1; - packet1.errors_count2 = packet_in.errors_count2; - packet1.errors_count3 = packet_in.errors_count3; - packet1.errors_count4 = packet_in.errors_count4; - packet1.battery_remaining = packet_in.battery_remaining; - packet1.onboard_control_sensors_present_extended = packet_in.onboard_control_sensors_present_extended; - packet1.onboard_control_sensors_enabled_extended = packet_in.onboard_control_sensors_enabled_extended; - packet1.onboard_control_sensors_health_extended = packet_in.onboard_control_sensors_health_extended; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_SYS_STATUS_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SYS_STATUS_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_sys_status_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_sys_status_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_sys_status_pack(system_id, component_id, &msg , packet1.onboard_control_sensors_present , packet1.onboard_control_sensors_enabled , packet1.onboard_control_sensors_health , packet1.load , packet1.voltage_battery , packet1.current_battery , packet1.battery_remaining , packet1.drop_rate_comm , packet1.errors_comm , packet1.errors_count1 , packet1.errors_count2 , packet1.errors_count3 , packet1.errors_count4 , packet1.onboard_control_sensors_present_extended , packet1.onboard_control_sensors_enabled_extended , packet1.onboard_control_sensors_health_extended ); - mavlink_msg_sys_status_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_sys_status_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.onboard_control_sensors_present , packet1.onboard_control_sensors_enabled , packet1.onboard_control_sensors_health , packet1.load , packet1.voltage_battery , packet1.current_battery , packet1.battery_remaining , packet1.drop_rate_comm , packet1.errors_comm , packet1.errors_count1 , packet1.errors_count2 , packet1.errors_count3 , packet1.errors_count4 , packet1.onboard_control_sensors_present_extended , packet1.onboard_control_sensors_enabled_extended , packet1.onboard_control_sensors_health_extended ); - mavlink_msg_sys_status_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_SYSTEM_TIME >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_system_time_t packet_in = { - 93372036854775807ULL,963497880 - }; - mavlink_system_time_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_unix_usec = packet_in.time_unix_usec; - packet1.time_boot_ms = packet_in.time_boot_ms; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_SYSTEM_TIME_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SYSTEM_TIME_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_system_time_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_system_time_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_system_time_pack(system_id, component_id, &msg , packet1.time_unix_usec , packet1.time_boot_ms ); - mavlink_msg_system_time_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_system_time_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_unix_usec , packet1.time_boot_ms ); - mavlink_msg_system_time_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_PING >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_ping_t packet_in = { - 93372036854775807ULL,963497880,41,108 - }; - mavlink_ping_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_usec = packet_in.time_usec; - packet1.seq = packet_in.seq; - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_PING_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_PING_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_ping_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_ping_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_ping_pack(system_id, component_id, &msg , packet1.time_usec , packet1.seq , packet1.target_system , packet1.target_component ); - mavlink_msg_ping_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_ping_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.seq , packet1.target_system , packet1.target_component ); - mavlink_msg_ping_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_change_operator_control_t packet_in = { - 5,72,139,"DEFGHIJKLMNOPQRSTUVWXYZA" - }; - mavlink_change_operator_control_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.target_system = packet_in.target_system; - packet1.control_request = packet_in.control_request; - packet1.version = packet_in.version; - - mav_array_memcpy(packet1.passkey, packet_in.passkey, sizeof(char)*25); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_change_operator_control_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_change_operator_control_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_change_operator_control_pack(system_id, component_id, &msg , packet1.target_system , packet1.control_request , packet1.version , packet1.passkey ); - mavlink_msg_change_operator_control_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_change_operator_control_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.control_request , packet1.version , packet1.passkey ); - mavlink_msg_change_operator_control_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_change_operator_control_ack_t packet_in = { - 5,72,139 - }; - mavlink_change_operator_control_ack_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.gcs_system_id = packet_in.gcs_system_id; - packet1.control_request = packet_in.control_request; - packet1.ack = packet_in.ack; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_change_operator_control_ack_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_change_operator_control_ack_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_change_operator_control_ack_pack(system_id, component_id, &msg , packet1.gcs_system_id , packet1.control_request , packet1.ack ); - mavlink_msg_change_operator_control_ack_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_change_operator_control_ack_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.gcs_system_id , packet1.control_request , packet1.ack ); - mavlink_msg_change_operator_control_ack_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_AUTH_KEY >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_auth_key_t packet_in = { - "ABCDEFGHIJKLMNOPQRSTUVWXYZABCDE" - }; - mavlink_auth_key_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - - mav_array_memcpy(packet1.key, packet_in.key, sizeof(char)*32); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_AUTH_KEY_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_AUTH_KEY_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_auth_key_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_auth_key_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_auth_key_pack(system_id, component_id, &msg , packet1.key ); - mavlink_msg_auth_key_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_auth_key_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.key ); - mavlink_msg_auth_key_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_LINK_NODE_STATUS >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_link_node_status_t packet_in = { - 93372036854775807ULL,963497880,963498088,963498296,963498504,963498712,18691,18795,18899,235,46 - }; - mavlink_link_node_status_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.timestamp = packet_in.timestamp; - packet1.tx_rate = packet_in.tx_rate; - packet1.rx_rate = packet_in.rx_rate; - packet1.messages_sent = packet_in.messages_sent; - packet1.messages_received = packet_in.messages_received; - packet1.messages_lost = packet_in.messages_lost; - packet1.rx_parse_err = packet_in.rx_parse_err; - packet1.tx_overflows = packet_in.tx_overflows; - packet1.rx_overflows = packet_in.rx_overflows; - packet1.tx_buf = packet_in.tx_buf; - packet1.rx_buf = packet_in.rx_buf; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_LINK_NODE_STATUS_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_LINK_NODE_STATUS_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_link_node_status_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_link_node_status_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_link_node_status_pack(system_id, component_id, &msg , packet1.timestamp , packet1.tx_buf , packet1.rx_buf , packet1.tx_rate , packet1.rx_rate , packet1.rx_parse_err , packet1.tx_overflows , packet1.rx_overflows , packet1.messages_sent , packet1.messages_received , packet1.messages_lost ); - mavlink_msg_link_node_status_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_link_node_status_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.tx_buf , packet1.rx_buf , packet1.tx_rate , packet1.rx_rate , packet1.rx_parse_err , packet1.tx_overflows , packet1.rx_overflows , packet1.messages_sent , packet1.messages_received , packet1.messages_lost ); - mavlink_msg_link_node_status_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_SET_MODE >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_set_mode_t packet_in = { - 963497464,17,84 - }; - mavlink_set_mode_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.custom_mode = packet_in.custom_mode; - packet1.target_system = packet_in.target_system; - packet1.base_mode = packet_in.base_mode; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_SET_MODE_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SET_MODE_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_set_mode_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_set_mode_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_set_mode_pack(system_id, component_id, &msg , packet1.target_system , packet1.base_mode , packet1.custom_mode ); - mavlink_msg_set_mode_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_set_mode_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.base_mode , packet1.custom_mode ); - mavlink_msg_set_mode_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_PARAM_REQUEST_READ >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_param_request_read_t packet_in = { - 17235,139,206,"EFGHIJKLMNOPQRS" - }; - mavlink_param_request_read_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.param_index = packet_in.param_index; - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - - mav_array_memcpy(packet1.param_id, packet_in.param_id, sizeof(char)*16); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_PARAM_REQUEST_READ_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_PARAM_REQUEST_READ_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_param_request_read_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_param_request_read_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_param_request_read_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.param_id , packet1.param_index ); - mavlink_msg_param_request_read_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_param_request_read_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.param_id , packet1.param_index ); - mavlink_msg_param_request_read_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_PARAM_REQUEST_LIST >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_param_request_list_t packet_in = { - 5,72 - }; - mavlink_param_request_list_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_PARAM_REQUEST_LIST_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_PARAM_REQUEST_LIST_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_param_request_list_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_param_request_list_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_param_request_list_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component ); - mavlink_msg_param_request_list_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_param_request_list_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component ); - mavlink_msg_param_request_list_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_PARAM_VALUE >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_param_value_t packet_in = { - 17.0,17443,17547,"IJKLMNOPQRSTUVW",77 - }; - mavlink_param_value_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.param_value = packet_in.param_value; - packet1.param_count = packet_in.param_count; - packet1.param_index = packet_in.param_index; - packet1.param_type = packet_in.param_type; - - mav_array_memcpy(packet1.param_id, packet_in.param_id, sizeof(char)*16); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_PARAM_VALUE_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_PARAM_VALUE_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_param_value_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_param_value_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_param_value_pack(system_id, component_id, &msg , packet1.param_id , packet1.param_value , packet1.param_type , packet1.param_count , packet1.param_index ); - mavlink_msg_param_value_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_param_value_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.param_id , packet1.param_value , packet1.param_type , packet1.param_count , packet1.param_index ); - mavlink_msg_param_value_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_PARAM_SET >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_param_set_t packet_in = { - 17.0,17,84,"GHIJKLMNOPQRSTU",199 - }; - mavlink_param_set_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.param_value = packet_in.param_value; - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - packet1.param_type = packet_in.param_type; - - mav_array_memcpy(packet1.param_id, packet_in.param_id, sizeof(char)*16); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_PARAM_SET_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_PARAM_SET_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_param_set_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_param_set_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_param_set_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.param_id , packet1.param_value , packet1.param_type ); - mavlink_msg_param_set_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_param_set_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.param_id , packet1.param_value , packet1.param_type ); - mavlink_msg_param_set_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_GPS_RAW_INT >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_gps_raw_int_t packet_in = { - 93372036854775807ULL,963497880,963498088,963498296,18275,18379,18483,18587,89,156,963499024,963499232,963499440,963499648,963499856,19835 - }; - mavlink_gps_raw_int_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_usec = packet_in.time_usec; - packet1.lat = packet_in.lat; - packet1.lon = packet_in.lon; - packet1.alt = packet_in.alt; - packet1.eph = packet_in.eph; - packet1.epv = packet_in.epv; - packet1.vel = packet_in.vel; - packet1.cog = packet_in.cog; - packet1.fix_type = packet_in.fix_type; - packet1.satellites_visible = packet_in.satellites_visible; - packet1.alt_ellipsoid = packet_in.alt_ellipsoid; - packet1.h_acc = packet_in.h_acc; - packet1.v_acc = packet_in.v_acc; - packet1.vel_acc = packet_in.vel_acc; - packet1.hdg_acc = packet_in.hdg_acc; - packet1.yaw = packet_in.yaw; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_GPS_RAW_INT_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_GPS_RAW_INT_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_gps_raw_int_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_gps_raw_int_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_gps_raw_int_pack(system_id, component_id, &msg , packet1.time_usec , packet1.fix_type , packet1.lat , packet1.lon , packet1.alt , packet1.eph , packet1.epv , packet1.vel , packet1.cog , packet1.satellites_visible , packet1.alt_ellipsoid , packet1.h_acc , packet1.v_acc , packet1.vel_acc , packet1.hdg_acc , packet1.yaw ); - mavlink_msg_gps_raw_int_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_gps_raw_int_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.fix_type , packet1.lat , packet1.lon , packet1.alt , packet1.eph , packet1.epv , packet1.vel , packet1.cog , packet1.satellites_visible , packet1.alt_ellipsoid , packet1.h_acc , packet1.v_acc , packet1.vel_acc , packet1.hdg_acc , packet1.yaw ); - mavlink_msg_gps_raw_int_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_GPS_STATUS >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_gps_status_t packet_in = { - 5,{ 72, 73, 74, 75, 76, 77, 78, 79, 80, 81, 82, 83, 84, 85, 86, 87, 88, 89, 90, 91 },{ 132, 133, 134, 135, 136, 137, 138, 139, 140, 141, 142, 143, 144, 145, 146, 147, 148, 149, 150, 151 },{ 192, 193, 194, 195, 196, 197, 198, 199, 200, 201, 202, 203, 204, 205, 206, 207, 208, 209, 210, 211 },{ 252, 253, 254, 255, 0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15 },{ 56, 57, 58, 59, 60, 61, 62, 63, 64, 65, 66, 67, 68, 69, 70, 71, 72, 73, 74, 75 } - }; - mavlink_gps_status_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.satellites_visible = packet_in.satellites_visible; - - mav_array_memcpy(packet1.satellite_prn, packet_in.satellite_prn, sizeof(uint8_t)*20); - mav_array_memcpy(packet1.satellite_used, packet_in.satellite_used, sizeof(uint8_t)*20); - mav_array_memcpy(packet1.satellite_elevation, packet_in.satellite_elevation, sizeof(uint8_t)*20); - mav_array_memcpy(packet1.satellite_azimuth, packet_in.satellite_azimuth, sizeof(uint8_t)*20); - mav_array_memcpy(packet1.satellite_snr, packet_in.satellite_snr, sizeof(uint8_t)*20); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_GPS_STATUS_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_GPS_STATUS_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_gps_status_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_gps_status_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_gps_status_pack(system_id, component_id, &msg , packet1.satellites_visible , packet1.satellite_prn , packet1.satellite_used , packet1.satellite_elevation , packet1.satellite_azimuth , packet1.satellite_snr ); - mavlink_msg_gps_status_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_gps_status_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.satellites_visible , packet1.satellite_prn , packet1.satellite_used , packet1.satellite_elevation , packet1.satellite_azimuth , packet1.satellite_snr ); - mavlink_msg_gps_status_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_SCALED_IMU >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_scaled_imu_t packet_in = { - 963497464,17443,17547,17651,17755,17859,17963,18067,18171,18275,18379 - }; - mavlink_scaled_imu_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_boot_ms = packet_in.time_boot_ms; - packet1.xacc = packet_in.xacc; - packet1.yacc = packet_in.yacc; - packet1.zacc = packet_in.zacc; - packet1.xgyro = packet_in.xgyro; - packet1.ygyro = packet_in.ygyro; - packet1.zgyro = packet_in.zgyro; - packet1.xmag = packet_in.xmag; - packet1.ymag = packet_in.ymag; - packet1.zmag = packet_in.zmag; - packet1.temperature = packet_in.temperature; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_SCALED_IMU_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SCALED_IMU_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_scaled_imu_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_scaled_imu_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_scaled_imu_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.xacc , packet1.yacc , packet1.zacc , packet1.xgyro , packet1.ygyro , packet1.zgyro , packet1.xmag , packet1.ymag , packet1.zmag , packet1.temperature ); - mavlink_msg_scaled_imu_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_scaled_imu_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.xacc , packet1.yacc , packet1.zacc , packet1.xgyro , packet1.ygyro , packet1.zgyro , packet1.xmag , packet1.ymag , packet1.zmag , packet1.temperature ); - mavlink_msg_scaled_imu_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_RAW_IMU >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_raw_imu_t packet_in = { - 93372036854775807ULL,17651,17755,17859,17963,18067,18171,18275,18379,18483,211,18639 - }; - mavlink_raw_imu_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_usec = packet_in.time_usec; - packet1.xacc = packet_in.xacc; - packet1.yacc = packet_in.yacc; - packet1.zacc = packet_in.zacc; - packet1.xgyro = packet_in.xgyro; - packet1.ygyro = packet_in.ygyro; - packet1.zgyro = packet_in.zgyro; - packet1.xmag = packet_in.xmag; - packet1.ymag = packet_in.ymag; - packet1.zmag = packet_in.zmag; - packet1.id = packet_in.id; - packet1.temperature = packet_in.temperature; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_RAW_IMU_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_RAW_IMU_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_raw_imu_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_raw_imu_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_raw_imu_pack(system_id, component_id, &msg , packet1.time_usec , packet1.xacc , packet1.yacc , packet1.zacc , packet1.xgyro , packet1.ygyro , packet1.zgyro , packet1.xmag , packet1.ymag , packet1.zmag , packet1.id , packet1.temperature ); - mavlink_msg_raw_imu_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_raw_imu_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.xacc , packet1.yacc , packet1.zacc , packet1.xgyro , packet1.ygyro , packet1.zgyro , packet1.xmag , packet1.ymag , packet1.zmag , packet1.id , packet1.temperature ); - mavlink_msg_raw_imu_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_RAW_PRESSURE >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_raw_pressure_t packet_in = { - 93372036854775807ULL,17651,17755,17859,17963 - }; - mavlink_raw_pressure_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_usec = packet_in.time_usec; - packet1.press_abs = packet_in.press_abs; - packet1.press_diff1 = packet_in.press_diff1; - packet1.press_diff2 = packet_in.press_diff2; - packet1.temperature = packet_in.temperature; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_RAW_PRESSURE_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_RAW_PRESSURE_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_raw_pressure_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_raw_pressure_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_raw_pressure_pack(system_id, component_id, &msg , packet1.time_usec , packet1.press_abs , packet1.press_diff1 , packet1.press_diff2 , packet1.temperature ); - mavlink_msg_raw_pressure_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_raw_pressure_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.press_abs , packet1.press_diff1 , packet1.press_diff2 , packet1.temperature ); - mavlink_msg_raw_pressure_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_SCALED_PRESSURE >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_scaled_pressure_t packet_in = { - 963497464,45.0,73.0,17859,17963 - }; - mavlink_scaled_pressure_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_boot_ms = packet_in.time_boot_ms; - packet1.press_abs = packet_in.press_abs; - packet1.press_diff = packet_in.press_diff; - packet1.temperature = packet_in.temperature; - packet1.temperature_press_diff = packet_in.temperature_press_diff; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_SCALED_PRESSURE_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SCALED_PRESSURE_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_scaled_pressure_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_scaled_pressure_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_scaled_pressure_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.press_abs , packet1.press_diff , packet1.temperature , packet1.temperature_press_diff ); - mavlink_msg_scaled_pressure_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_scaled_pressure_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.press_abs , packet1.press_diff , packet1.temperature , packet1.temperature_press_diff ); - mavlink_msg_scaled_pressure_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_ATTITUDE >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_attitude_t packet_in = { - 963497464,45.0,73.0,101.0,129.0,157.0,185.0 - }; - mavlink_attitude_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_boot_ms = packet_in.time_boot_ms; - packet1.roll = packet_in.roll; - packet1.pitch = packet_in.pitch; - packet1.yaw = packet_in.yaw; - packet1.rollspeed = packet_in.rollspeed; - packet1.pitchspeed = packet_in.pitchspeed; - packet1.yawspeed = packet_in.yawspeed; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_ATTITUDE_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_ATTITUDE_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_attitude_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_attitude_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_attitude_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.roll , packet1.pitch , packet1.yaw , packet1.rollspeed , packet1.pitchspeed , packet1.yawspeed ); - mavlink_msg_attitude_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_attitude_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.roll , packet1.pitch , packet1.yaw , packet1.rollspeed , packet1.pitchspeed , packet1.yawspeed ); - mavlink_msg_attitude_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_ATTITUDE_QUATERNION >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_attitude_quaternion_t packet_in = { - 963497464,45.0,73.0,101.0,129.0,157.0,185.0,213.0,{ 241.0, 242.0, 243.0, 244.0 } - }; - mavlink_attitude_quaternion_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_boot_ms = packet_in.time_boot_ms; - packet1.q1 = packet_in.q1; - packet1.q2 = packet_in.q2; - packet1.q3 = packet_in.q3; - packet1.q4 = packet_in.q4; - packet1.rollspeed = packet_in.rollspeed; - packet1.pitchspeed = packet_in.pitchspeed; - packet1.yawspeed = packet_in.yawspeed; - - mav_array_memcpy(packet1.repr_offset_q, packet_in.repr_offset_q, sizeof(float)*4); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_ATTITUDE_QUATERNION_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_ATTITUDE_QUATERNION_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_attitude_quaternion_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_attitude_quaternion_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_attitude_quaternion_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.q1 , packet1.q2 , packet1.q3 , packet1.q4 , packet1.rollspeed , packet1.pitchspeed , packet1.yawspeed , packet1.repr_offset_q ); - mavlink_msg_attitude_quaternion_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_attitude_quaternion_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.q1 , packet1.q2 , packet1.q3 , packet1.q4 , packet1.rollspeed , packet1.pitchspeed , packet1.yawspeed , packet1.repr_offset_q ); - mavlink_msg_attitude_quaternion_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_LOCAL_POSITION_NED >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_local_position_ned_t packet_in = { - 963497464,45.0,73.0,101.0,129.0,157.0,185.0 - }; - mavlink_local_position_ned_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_boot_ms = packet_in.time_boot_ms; - packet1.x = packet_in.x; - packet1.y = packet_in.y; - packet1.z = packet_in.z; - packet1.vx = packet_in.vx; - packet1.vy = packet_in.vy; - packet1.vz = packet_in.vz; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_LOCAL_POSITION_NED_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_LOCAL_POSITION_NED_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_local_position_ned_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_local_position_ned_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_local_position_ned_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.x , packet1.y , packet1.z , packet1.vx , packet1.vy , packet1.vz ); - mavlink_msg_local_position_ned_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_local_position_ned_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.x , packet1.y , packet1.z , packet1.vx , packet1.vy , packet1.vz ); - mavlink_msg_local_position_ned_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_GLOBAL_POSITION_INT >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_global_position_int_t packet_in = { - 963497464,963497672,963497880,963498088,963498296,18275,18379,18483,18587 - }; - mavlink_global_position_int_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_boot_ms = packet_in.time_boot_ms; - packet1.lat = packet_in.lat; - packet1.lon = packet_in.lon; - packet1.alt = packet_in.alt; - packet1.relative_alt = packet_in.relative_alt; - packet1.vx = packet_in.vx; - packet1.vy = packet_in.vy; - packet1.vz = packet_in.vz; - packet1.hdg = packet_in.hdg; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_GLOBAL_POSITION_INT_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_GLOBAL_POSITION_INT_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_global_position_int_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_global_position_int_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_global_position_int_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.lat , packet1.lon , packet1.alt , packet1.relative_alt , packet1.vx , packet1.vy , packet1.vz , packet1.hdg ); - mavlink_msg_global_position_int_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_global_position_int_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.lat , packet1.lon , packet1.alt , packet1.relative_alt , packet1.vx , packet1.vy , packet1.vz , packet1.hdg ); - mavlink_msg_global_position_int_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_RC_CHANNELS_SCALED >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_rc_channels_scaled_t packet_in = { - 963497464,17443,17547,17651,17755,17859,17963,18067,18171,65,132 - }; - mavlink_rc_channels_scaled_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_boot_ms = packet_in.time_boot_ms; - packet1.chan1_scaled = packet_in.chan1_scaled; - packet1.chan2_scaled = packet_in.chan2_scaled; - packet1.chan3_scaled = packet_in.chan3_scaled; - packet1.chan4_scaled = packet_in.chan4_scaled; - packet1.chan5_scaled = packet_in.chan5_scaled; - packet1.chan6_scaled = packet_in.chan6_scaled; - packet1.chan7_scaled = packet_in.chan7_scaled; - packet1.chan8_scaled = packet_in.chan8_scaled; - packet1.port = packet_in.port; - packet1.rssi = packet_in.rssi; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_RC_CHANNELS_SCALED_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_RC_CHANNELS_SCALED_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_rc_channels_scaled_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_rc_channels_scaled_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_rc_channels_scaled_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.port , packet1.chan1_scaled , packet1.chan2_scaled , packet1.chan3_scaled , packet1.chan4_scaled , packet1.chan5_scaled , packet1.chan6_scaled , packet1.chan7_scaled , packet1.chan8_scaled , packet1.rssi ); - mavlink_msg_rc_channels_scaled_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_rc_channels_scaled_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.port , packet1.chan1_scaled , packet1.chan2_scaled , packet1.chan3_scaled , packet1.chan4_scaled , packet1.chan5_scaled , packet1.chan6_scaled , packet1.chan7_scaled , packet1.chan8_scaled , packet1.rssi ); - mavlink_msg_rc_channels_scaled_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_RC_CHANNELS_RAW >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_rc_channels_raw_t packet_in = { - 963497464,17443,17547,17651,17755,17859,17963,18067,18171,65,132 - }; - mavlink_rc_channels_raw_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_boot_ms = packet_in.time_boot_ms; - packet1.chan1_raw = packet_in.chan1_raw; - packet1.chan2_raw = packet_in.chan2_raw; - packet1.chan3_raw = packet_in.chan3_raw; - packet1.chan4_raw = packet_in.chan4_raw; - packet1.chan5_raw = packet_in.chan5_raw; - packet1.chan6_raw = packet_in.chan6_raw; - packet1.chan7_raw = packet_in.chan7_raw; - packet1.chan8_raw = packet_in.chan8_raw; - packet1.port = packet_in.port; - packet1.rssi = packet_in.rssi; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_RC_CHANNELS_RAW_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_RC_CHANNELS_RAW_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_rc_channels_raw_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_rc_channels_raw_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_rc_channels_raw_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.port , packet1.chan1_raw , packet1.chan2_raw , packet1.chan3_raw , packet1.chan4_raw , packet1.chan5_raw , packet1.chan6_raw , packet1.chan7_raw , packet1.chan8_raw , packet1.rssi ); - mavlink_msg_rc_channels_raw_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_rc_channels_raw_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.port , packet1.chan1_raw , packet1.chan2_raw , packet1.chan3_raw , packet1.chan4_raw , packet1.chan5_raw , packet1.chan6_raw , packet1.chan7_raw , packet1.chan8_raw , packet1.rssi ); - mavlink_msg_rc_channels_raw_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_SERVO_OUTPUT_RAW >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_servo_output_raw_t packet_in = { - 963497464,17443,17547,17651,17755,17859,17963,18067,18171,65,18327,18431,18535,18639,18743,18847,18951,19055 - }; - mavlink_servo_output_raw_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_usec = packet_in.time_usec; - packet1.servo1_raw = packet_in.servo1_raw; - packet1.servo2_raw = packet_in.servo2_raw; - packet1.servo3_raw = packet_in.servo3_raw; - packet1.servo4_raw = packet_in.servo4_raw; - packet1.servo5_raw = packet_in.servo5_raw; - packet1.servo6_raw = packet_in.servo6_raw; - packet1.servo7_raw = packet_in.servo7_raw; - packet1.servo8_raw = packet_in.servo8_raw; - packet1.port = packet_in.port; - packet1.servo9_raw = packet_in.servo9_raw; - packet1.servo10_raw = packet_in.servo10_raw; - packet1.servo11_raw = packet_in.servo11_raw; - packet1.servo12_raw = packet_in.servo12_raw; - packet1.servo13_raw = packet_in.servo13_raw; - packet1.servo14_raw = packet_in.servo14_raw; - packet1.servo15_raw = packet_in.servo15_raw; - packet1.servo16_raw = packet_in.servo16_raw; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_servo_output_raw_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_servo_output_raw_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_servo_output_raw_pack(system_id, component_id, &msg , packet1.time_usec , packet1.port , packet1.servo1_raw , packet1.servo2_raw , packet1.servo3_raw , packet1.servo4_raw , packet1.servo5_raw , packet1.servo6_raw , packet1.servo7_raw , packet1.servo8_raw , packet1.servo9_raw , packet1.servo10_raw , packet1.servo11_raw , packet1.servo12_raw , packet1.servo13_raw , packet1.servo14_raw , packet1.servo15_raw , packet1.servo16_raw ); - mavlink_msg_servo_output_raw_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_servo_output_raw_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.port , packet1.servo1_raw , packet1.servo2_raw , packet1.servo3_raw , packet1.servo4_raw , packet1.servo5_raw , packet1.servo6_raw , packet1.servo7_raw , packet1.servo8_raw , packet1.servo9_raw , packet1.servo10_raw , packet1.servo11_raw , packet1.servo12_raw , packet1.servo13_raw , packet1.servo14_raw , packet1.servo15_raw , packet1.servo16_raw ); - mavlink_msg_servo_output_raw_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_mission_request_partial_list_t packet_in = { - 17235,17339,17,84,151 - }; - mavlink_mission_request_partial_list_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.start_index = packet_in.start_index; - packet1.end_index = packet_in.end_index; - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - packet1.mission_type = packet_in.mission_type; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_mission_request_partial_list_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_mission_request_partial_list_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_mission_request_partial_list_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.start_index , packet1.end_index , packet1.mission_type ); - mavlink_msg_mission_request_partial_list_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_mission_request_partial_list_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.start_index , packet1.end_index , packet1.mission_type ); - mavlink_msg_mission_request_partial_list_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_mission_write_partial_list_t packet_in = { - 17235,17339,17,84,151 - }; - mavlink_mission_write_partial_list_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.start_index = packet_in.start_index; - packet1.end_index = packet_in.end_index; - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - packet1.mission_type = packet_in.mission_type; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_mission_write_partial_list_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_mission_write_partial_list_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_mission_write_partial_list_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.start_index , packet1.end_index , packet1.mission_type ); - mavlink_msg_mission_write_partial_list_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_mission_write_partial_list_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.start_index , packet1.end_index , packet1.mission_type ); - mavlink_msg_mission_write_partial_list_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_MISSION_ITEM >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_mission_item_t packet_in = { - 17.0,45.0,73.0,101.0,129.0,157.0,185.0,18691,18795,101,168,235,46,113,180 - }; - mavlink_mission_item_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.param1 = packet_in.param1; - packet1.param2 = packet_in.param2; - packet1.param3 = packet_in.param3; - packet1.param4 = packet_in.param4; - packet1.x = packet_in.x; - packet1.y = packet_in.y; - packet1.z = packet_in.z; - packet1.seq = packet_in.seq; - packet1.command = packet_in.command; - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - packet1.frame = packet_in.frame; - packet1.current = packet_in.current; - packet1.autocontinue = packet_in.autocontinue; - packet1.mission_type = packet_in.mission_type; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_MISSION_ITEM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_MISSION_ITEM_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_mission_item_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_mission_item_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_mission_item_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.seq , packet1.frame , packet1.command , packet1.current , packet1.autocontinue , packet1.param1 , packet1.param2 , packet1.param3 , packet1.param4 , packet1.x , packet1.y , packet1.z , packet1.mission_type ); - mavlink_msg_mission_item_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_mission_item_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.seq , packet1.frame , packet1.command , packet1.current , packet1.autocontinue , packet1.param1 , packet1.param2 , packet1.param3 , packet1.param4 , packet1.x , packet1.y , packet1.z , packet1.mission_type ); - mavlink_msg_mission_item_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_MISSION_REQUEST >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_mission_request_t packet_in = { - 17235,139,206,17 - }; - mavlink_mission_request_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.seq = packet_in.seq; - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - packet1.mission_type = packet_in.mission_type; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_MISSION_REQUEST_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_MISSION_REQUEST_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_mission_request_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_mission_request_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_mission_request_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.seq , packet1.mission_type ); - mavlink_msg_mission_request_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_mission_request_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.seq , packet1.mission_type ); - mavlink_msg_mission_request_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_MISSION_SET_CURRENT >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_mission_set_current_t packet_in = { - 17235,139,206 - }; - mavlink_mission_set_current_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.seq = packet_in.seq; - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_MISSION_SET_CURRENT_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_MISSION_SET_CURRENT_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_mission_set_current_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_mission_set_current_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_mission_set_current_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.seq ); - mavlink_msg_mission_set_current_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_mission_set_current_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.seq ); - mavlink_msg_mission_set_current_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_MISSION_CURRENT >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_mission_current_t packet_in = { - 17235,17339,17,84 - }; - mavlink_mission_current_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.seq = packet_in.seq; - packet1.total = packet_in.total; - packet1.mission_state = packet_in.mission_state; - packet1.mission_mode = packet_in.mission_mode; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_MISSION_CURRENT_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_MISSION_CURRENT_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_mission_current_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_mission_current_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_mission_current_pack(system_id, component_id, &msg , packet1.seq , packet1.total , packet1.mission_state , packet1.mission_mode ); - mavlink_msg_mission_current_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_mission_current_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.seq , packet1.total , packet1.mission_state , packet1.mission_mode ); - mavlink_msg_mission_current_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_MISSION_REQUEST_LIST >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_mission_request_list_t packet_in = { - 5,72,139 - }; - mavlink_mission_request_list_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - packet1.mission_type = packet_in.mission_type; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_MISSION_REQUEST_LIST_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_MISSION_REQUEST_LIST_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_mission_request_list_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_mission_request_list_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_mission_request_list_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.mission_type ); - mavlink_msg_mission_request_list_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_mission_request_list_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.mission_type ); - mavlink_msg_mission_request_list_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_MISSION_COUNT >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_mission_count_t packet_in = { - 17235,139,206,17 - }; - mavlink_mission_count_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.count = packet_in.count; - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - packet1.mission_type = packet_in.mission_type; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_MISSION_COUNT_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_MISSION_COUNT_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_mission_count_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_mission_count_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_mission_count_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.count , packet1.mission_type ); - mavlink_msg_mission_count_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_mission_count_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.count , packet1.mission_type ); - mavlink_msg_mission_count_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_MISSION_CLEAR_ALL >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_mission_clear_all_t packet_in = { - 5,72,139 - }; - mavlink_mission_clear_all_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - packet1.mission_type = packet_in.mission_type; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_MISSION_CLEAR_ALL_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_MISSION_CLEAR_ALL_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_mission_clear_all_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_mission_clear_all_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_mission_clear_all_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.mission_type ); - mavlink_msg_mission_clear_all_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_mission_clear_all_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.mission_type ); - mavlink_msg_mission_clear_all_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_MISSION_ITEM_REACHED >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_mission_item_reached_t packet_in = { - 17235 - }; - mavlink_mission_item_reached_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.seq = packet_in.seq; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_MISSION_ITEM_REACHED_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_MISSION_ITEM_REACHED_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_mission_item_reached_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_mission_item_reached_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_mission_item_reached_pack(system_id, component_id, &msg , packet1.seq ); - mavlink_msg_mission_item_reached_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_mission_item_reached_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.seq ); - mavlink_msg_mission_item_reached_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_MISSION_ACK >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_mission_ack_t packet_in = { - 5,72,139,206 - }; - mavlink_mission_ack_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - packet1.type = packet_in.type; - packet1.mission_type = packet_in.mission_type; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_MISSION_ACK_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_MISSION_ACK_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_mission_ack_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_mission_ack_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_mission_ack_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.type , packet1.mission_type ); - mavlink_msg_mission_ack_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_mission_ack_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.type , packet1.mission_type ); - mavlink_msg_mission_ack_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_set_gps_global_origin_t packet_in = { - 963497464,963497672,963497880,41,93372036854776626ULL - }; - mavlink_set_gps_global_origin_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.latitude = packet_in.latitude; - packet1.longitude = packet_in.longitude; - packet1.altitude = packet_in.altitude; - packet1.target_system = packet_in.target_system; - packet1.time_usec = packet_in.time_usec; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_set_gps_global_origin_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_set_gps_global_origin_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_set_gps_global_origin_pack(system_id, component_id, &msg , packet1.target_system , packet1.latitude , packet1.longitude , packet1.altitude , packet1.time_usec ); - mavlink_msg_set_gps_global_origin_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_set_gps_global_origin_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.latitude , packet1.longitude , packet1.altitude , packet1.time_usec ); - mavlink_msg_set_gps_global_origin_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_gps_global_origin_t packet_in = { - 963497464,963497672,963497880,93372036854776563ULL - }; - mavlink_gps_global_origin_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.latitude = packet_in.latitude; - packet1.longitude = packet_in.longitude; - packet1.altitude = packet_in.altitude; - packet1.time_usec = packet_in.time_usec; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_gps_global_origin_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_gps_global_origin_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_gps_global_origin_pack(system_id, component_id, &msg , packet1.latitude , packet1.longitude , packet1.altitude , packet1.time_usec ); - mavlink_msg_gps_global_origin_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_gps_global_origin_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.latitude , packet1.longitude , packet1.altitude , packet1.time_usec ); - mavlink_msg_gps_global_origin_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_PARAM_MAP_RC >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_param_map_rc_t packet_in = { - 17.0,45.0,73.0,101.0,18067,187,254,"UVWXYZABCDEFGHI",113 - }; - mavlink_param_map_rc_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.param_value0 = packet_in.param_value0; - packet1.scale = packet_in.scale; - packet1.param_value_min = packet_in.param_value_min; - packet1.param_value_max = packet_in.param_value_max; - packet1.param_index = packet_in.param_index; - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - packet1.parameter_rc_channel_index = packet_in.parameter_rc_channel_index; - - mav_array_memcpy(packet1.param_id, packet_in.param_id, sizeof(char)*16); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_PARAM_MAP_RC_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_PARAM_MAP_RC_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_param_map_rc_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_param_map_rc_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_param_map_rc_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.param_id , packet1.param_index , packet1.parameter_rc_channel_index , packet1.param_value0 , packet1.scale , packet1.param_value_min , packet1.param_value_max ); - mavlink_msg_param_map_rc_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_param_map_rc_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.param_id , packet1.param_index , packet1.parameter_rc_channel_index , packet1.param_value0 , packet1.scale , packet1.param_value_min , packet1.param_value_max ); - mavlink_msg_param_map_rc_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_MISSION_REQUEST_INT >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_mission_request_int_t packet_in = { - 17235,139,206,17 - }; - mavlink_mission_request_int_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.seq = packet_in.seq; - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - packet1.mission_type = packet_in.mission_type; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_MISSION_REQUEST_INT_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_MISSION_REQUEST_INT_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_mission_request_int_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_mission_request_int_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_mission_request_int_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.seq , packet1.mission_type ); - mavlink_msg_mission_request_int_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_mission_request_int_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.seq , packet1.mission_type ); - mavlink_msg_mission_request_int_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_safety_set_allowed_area_t packet_in = { - 17.0,45.0,73.0,101.0,129.0,157.0,77,144,211 - }; - mavlink_safety_set_allowed_area_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.p1x = packet_in.p1x; - packet1.p1y = packet_in.p1y; - packet1.p1z = packet_in.p1z; - packet1.p2x = packet_in.p2x; - packet1.p2y = packet_in.p2y; - packet1.p2z = packet_in.p2z; - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - packet1.frame = packet_in.frame; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_safety_set_allowed_area_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_safety_set_allowed_area_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_safety_set_allowed_area_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.frame , packet1.p1x , packet1.p1y , packet1.p1z , packet1.p2x , packet1.p2y , packet1.p2z ); - mavlink_msg_safety_set_allowed_area_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_safety_set_allowed_area_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.frame , packet1.p1x , packet1.p1y , packet1.p1z , packet1.p2x , packet1.p2y , packet1.p2z ); - mavlink_msg_safety_set_allowed_area_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_safety_allowed_area_t packet_in = { - 17.0,45.0,73.0,101.0,129.0,157.0,77 - }; - mavlink_safety_allowed_area_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.p1x = packet_in.p1x; - packet1.p1y = packet_in.p1y; - packet1.p1z = packet_in.p1z; - packet1.p2x = packet_in.p2x; - packet1.p2y = packet_in.p2y; - packet1.p2z = packet_in.p2z; - packet1.frame = packet_in.frame; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_safety_allowed_area_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_safety_allowed_area_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_safety_allowed_area_pack(system_id, component_id, &msg , packet1.frame , packet1.p1x , packet1.p1y , packet1.p1z , packet1.p2x , packet1.p2y , packet1.p2z ); - mavlink_msg_safety_allowed_area_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_safety_allowed_area_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.frame , packet1.p1x , packet1.p1y , packet1.p1z , packet1.p2x , packet1.p2y , packet1.p2z ); - mavlink_msg_safety_allowed_area_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_attitude_quaternion_cov_t packet_in = { - 93372036854775807ULL,{ 73.0, 74.0, 75.0, 76.0 },185.0,213.0,241.0,{ 269.0, 270.0, 271.0, 272.0, 273.0, 274.0, 275.0, 276.0, 277.0 } - }; - mavlink_attitude_quaternion_cov_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_usec = packet_in.time_usec; - packet1.rollspeed = packet_in.rollspeed; - packet1.pitchspeed = packet_in.pitchspeed; - packet1.yawspeed = packet_in.yawspeed; - - mav_array_memcpy(packet1.q, packet_in.q, sizeof(float)*4); - mav_array_memcpy(packet1.covariance, packet_in.covariance, sizeof(float)*9); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_attitude_quaternion_cov_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_attitude_quaternion_cov_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_attitude_quaternion_cov_pack(system_id, component_id, &msg , packet1.time_usec , packet1.q , packet1.rollspeed , packet1.pitchspeed , packet1.yawspeed , packet1.covariance ); - mavlink_msg_attitude_quaternion_cov_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_attitude_quaternion_cov_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.q , packet1.rollspeed , packet1.pitchspeed , packet1.yawspeed , packet1.covariance ); - mavlink_msg_attitude_quaternion_cov_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_nav_controller_output_t packet_in = { - 17.0,45.0,73.0,101.0,129.0,18275,18379,18483 - }; - mavlink_nav_controller_output_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.nav_roll = packet_in.nav_roll; - packet1.nav_pitch = packet_in.nav_pitch; - packet1.alt_error = packet_in.alt_error; - packet1.aspd_error = packet_in.aspd_error; - packet1.xtrack_error = packet_in.xtrack_error; - packet1.nav_bearing = packet_in.nav_bearing; - packet1.target_bearing = packet_in.target_bearing; - packet1.wp_dist = packet_in.wp_dist; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_nav_controller_output_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_nav_controller_output_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_nav_controller_output_pack(system_id, component_id, &msg , packet1.nav_roll , packet1.nav_pitch , packet1.nav_bearing , packet1.target_bearing , packet1.wp_dist , packet1.alt_error , packet1.aspd_error , packet1.xtrack_error ); - mavlink_msg_nav_controller_output_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_nav_controller_output_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.nav_roll , packet1.nav_pitch , packet1.nav_bearing , packet1.target_bearing , packet1.wp_dist , packet1.alt_error , packet1.aspd_error , packet1.xtrack_error ); - mavlink_msg_nav_controller_output_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_global_position_int_cov_t packet_in = { - 93372036854775807ULL,963497880,963498088,963498296,963498504,185.0,213.0,241.0,{ 269.0, 270.0, 271.0, 272.0, 273.0, 274.0, 275.0, 276.0, 277.0, 278.0, 279.0, 280.0, 281.0, 282.0, 283.0, 284.0, 285.0, 286.0, 287.0, 288.0, 289.0, 290.0, 291.0, 292.0, 293.0, 294.0, 295.0, 296.0, 297.0, 298.0, 299.0, 300.0, 301.0, 302.0, 303.0, 304.0 },33 - }; - mavlink_global_position_int_cov_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_usec = packet_in.time_usec; - packet1.lat = packet_in.lat; - packet1.lon = packet_in.lon; - packet1.alt = packet_in.alt; - packet1.relative_alt = packet_in.relative_alt; - packet1.vx = packet_in.vx; - packet1.vy = packet_in.vy; - packet1.vz = packet_in.vz; - packet1.estimator_type = packet_in.estimator_type; - - mav_array_memcpy(packet1.covariance, packet_in.covariance, sizeof(float)*36); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_global_position_int_cov_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_global_position_int_cov_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_global_position_int_cov_pack(system_id, component_id, &msg , packet1.time_usec , packet1.estimator_type , packet1.lat , packet1.lon , packet1.alt , packet1.relative_alt , packet1.vx , packet1.vy , packet1.vz , packet1.covariance ); - mavlink_msg_global_position_int_cov_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_global_position_int_cov_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.estimator_type , packet1.lat , packet1.lon , packet1.alt , packet1.relative_alt , packet1.vx , packet1.vy , packet1.vz , packet1.covariance ); - mavlink_msg_global_position_int_cov_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_local_position_ned_cov_t packet_in = { - 93372036854775807ULL,73.0,101.0,129.0,157.0,185.0,213.0,241.0,269.0,297.0,{ 325.0, 326.0, 327.0, 328.0, 329.0, 330.0, 331.0, 332.0, 333.0, 334.0, 335.0, 336.0, 337.0, 338.0, 339.0, 340.0, 341.0, 342.0, 343.0, 344.0, 345.0, 346.0, 347.0, 348.0, 349.0, 350.0, 351.0, 352.0, 353.0, 354.0, 355.0, 356.0, 357.0, 358.0, 359.0, 360.0, 361.0, 362.0, 363.0, 364.0, 365.0, 366.0, 367.0, 368.0, 369.0 },165 - }; - mavlink_local_position_ned_cov_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_usec = packet_in.time_usec; - packet1.x = packet_in.x; - packet1.y = packet_in.y; - packet1.z = packet_in.z; - packet1.vx = packet_in.vx; - packet1.vy = packet_in.vy; - packet1.vz = packet_in.vz; - packet1.ax = packet_in.ax; - packet1.ay = packet_in.ay; - packet1.az = packet_in.az; - packet1.estimator_type = packet_in.estimator_type; - - mav_array_memcpy(packet1.covariance, packet_in.covariance, sizeof(float)*45); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_local_position_ned_cov_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_local_position_ned_cov_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_local_position_ned_cov_pack(system_id, component_id, &msg , packet1.time_usec , packet1.estimator_type , packet1.x , packet1.y , packet1.z , packet1.vx , packet1.vy , packet1.vz , packet1.ax , packet1.ay , packet1.az , packet1.covariance ); - mavlink_msg_local_position_ned_cov_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_local_position_ned_cov_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.estimator_type , packet1.x , packet1.y , packet1.z , packet1.vx , packet1.vy , packet1.vz , packet1.ax , packet1.ay , packet1.az , packet1.covariance ); - mavlink_msg_local_position_ned_cov_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_RC_CHANNELS >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_rc_channels_t packet_in = { - 963497464,17443,17547,17651,17755,17859,17963,18067,18171,18275,18379,18483,18587,18691,18795,18899,19003,19107,19211,125,192 - }; - mavlink_rc_channels_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_boot_ms = packet_in.time_boot_ms; - packet1.chan1_raw = packet_in.chan1_raw; - packet1.chan2_raw = packet_in.chan2_raw; - packet1.chan3_raw = packet_in.chan3_raw; - packet1.chan4_raw = packet_in.chan4_raw; - packet1.chan5_raw = packet_in.chan5_raw; - packet1.chan6_raw = packet_in.chan6_raw; - packet1.chan7_raw = packet_in.chan7_raw; - packet1.chan8_raw = packet_in.chan8_raw; - packet1.chan9_raw = packet_in.chan9_raw; - packet1.chan10_raw = packet_in.chan10_raw; - packet1.chan11_raw = packet_in.chan11_raw; - packet1.chan12_raw = packet_in.chan12_raw; - packet1.chan13_raw = packet_in.chan13_raw; - packet1.chan14_raw = packet_in.chan14_raw; - packet1.chan15_raw = packet_in.chan15_raw; - packet1.chan16_raw = packet_in.chan16_raw; - packet1.chan17_raw = packet_in.chan17_raw; - packet1.chan18_raw = packet_in.chan18_raw; - packet1.chancount = packet_in.chancount; - packet1.rssi = packet_in.rssi; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_RC_CHANNELS_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_RC_CHANNELS_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_rc_channels_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_rc_channels_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_rc_channels_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.chancount , packet1.chan1_raw , packet1.chan2_raw , packet1.chan3_raw , packet1.chan4_raw , packet1.chan5_raw , packet1.chan6_raw , packet1.chan7_raw , packet1.chan8_raw , packet1.chan9_raw , packet1.chan10_raw , packet1.chan11_raw , packet1.chan12_raw , packet1.chan13_raw , packet1.chan14_raw , packet1.chan15_raw , packet1.chan16_raw , packet1.chan17_raw , packet1.chan18_raw , packet1.rssi ); - mavlink_msg_rc_channels_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_rc_channels_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.chancount , packet1.chan1_raw , packet1.chan2_raw , packet1.chan3_raw , packet1.chan4_raw , packet1.chan5_raw , packet1.chan6_raw , packet1.chan7_raw , packet1.chan8_raw , packet1.chan9_raw , packet1.chan10_raw , packet1.chan11_raw , packet1.chan12_raw , packet1.chan13_raw , packet1.chan14_raw , packet1.chan15_raw , packet1.chan16_raw , packet1.chan17_raw , packet1.chan18_raw , packet1.rssi ); - mavlink_msg_rc_channels_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_REQUEST_DATA_STREAM >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_request_data_stream_t packet_in = { - 17235,139,206,17,84 - }; - mavlink_request_data_stream_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.req_message_rate = packet_in.req_message_rate; - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - packet1.req_stream_id = packet_in.req_stream_id; - packet1.start_stop = packet_in.start_stop; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_REQUEST_DATA_STREAM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_REQUEST_DATA_STREAM_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_request_data_stream_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_request_data_stream_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_request_data_stream_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.req_stream_id , packet1.req_message_rate , packet1.start_stop ); - mavlink_msg_request_data_stream_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_request_data_stream_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.req_stream_id , packet1.req_message_rate , packet1.start_stop ); - mavlink_msg_request_data_stream_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_DATA_STREAM >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_data_stream_t packet_in = { - 17235,139,206 - }; - mavlink_data_stream_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.message_rate = packet_in.message_rate; - packet1.stream_id = packet_in.stream_id; - packet1.on_off = packet_in.on_off; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_DATA_STREAM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_DATA_STREAM_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_data_stream_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_data_stream_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_data_stream_pack(system_id, component_id, &msg , packet1.stream_id , packet1.message_rate , packet1.on_off ); - mavlink_msg_data_stream_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_data_stream_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.stream_id , packet1.message_rate , packet1.on_off ); - mavlink_msg_data_stream_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_MANUAL_CONTROL >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_manual_control_t packet_in = { - 17235,17339,17443,17547,17651,163,17807,108,17963,18067 - }; - mavlink_manual_control_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.x = packet_in.x; - packet1.y = packet_in.y; - packet1.z = packet_in.z; - packet1.r = packet_in.r; - packet1.buttons = packet_in.buttons; - packet1.target = packet_in.target; - packet1.buttons2 = packet_in.buttons2; - packet1.enabled_extensions = packet_in.enabled_extensions; - packet1.s = packet_in.s; - packet1.t = packet_in.t; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_MANUAL_CONTROL_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_MANUAL_CONTROL_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_manual_control_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_manual_control_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_manual_control_pack(system_id, component_id, &msg , packet1.target , packet1.x , packet1.y , packet1.z , packet1.r , packet1.buttons , packet1.buttons2 , packet1.enabled_extensions , packet1.s , packet1.t ); - mavlink_msg_manual_control_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_manual_control_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target , packet1.x , packet1.y , packet1.z , packet1.r , packet1.buttons , packet1.buttons2 , packet1.enabled_extensions , packet1.s , packet1.t ); - mavlink_msg_manual_control_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_rc_channels_override_t packet_in = { - 17235,17339,17443,17547,17651,17755,17859,17963,53,120,18171,18275,18379,18483,18587,18691,18795,18899,19003,19107 - }; - mavlink_rc_channels_override_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.chan1_raw = packet_in.chan1_raw; - packet1.chan2_raw = packet_in.chan2_raw; - packet1.chan3_raw = packet_in.chan3_raw; - packet1.chan4_raw = packet_in.chan4_raw; - packet1.chan5_raw = packet_in.chan5_raw; - packet1.chan6_raw = packet_in.chan6_raw; - packet1.chan7_raw = packet_in.chan7_raw; - packet1.chan8_raw = packet_in.chan8_raw; - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - packet1.chan9_raw = packet_in.chan9_raw; - packet1.chan10_raw = packet_in.chan10_raw; - packet1.chan11_raw = packet_in.chan11_raw; - packet1.chan12_raw = packet_in.chan12_raw; - packet1.chan13_raw = packet_in.chan13_raw; - packet1.chan14_raw = packet_in.chan14_raw; - packet1.chan15_raw = packet_in.chan15_raw; - packet1.chan16_raw = packet_in.chan16_raw; - packet1.chan17_raw = packet_in.chan17_raw; - packet1.chan18_raw = packet_in.chan18_raw; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_rc_channels_override_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_rc_channels_override_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_rc_channels_override_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.chan1_raw , packet1.chan2_raw , packet1.chan3_raw , packet1.chan4_raw , packet1.chan5_raw , packet1.chan6_raw , packet1.chan7_raw , packet1.chan8_raw , packet1.chan9_raw , packet1.chan10_raw , packet1.chan11_raw , packet1.chan12_raw , packet1.chan13_raw , packet1.chan14_raw , packet1.chan15_raw , packet1.chan16_raw , packet1.chan17_raw , packet1.chan18_raw ); - mavlink_msg_rc_channels_override_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_rc_channels_override_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.chan1_raw , packet1.chan2_raw , packet1.chan3_raw , packet1.chan4_raw , packet1.chan5_raw , packet1.chan6_raw , packet1.chan7_raw , packet1.chan8_raw , packet1.chan9_raw , packet1.chan10_raw , packet1.chan11_raw , packet1.chan12_raw , packet1.chan13_raw , packet1.chan14_raw , packet1.chan15_raw , packet1.chan16_raw , packet1.chan17_raw , packet1.chan18_raw ); - mavlink_msg_rc_channels_override_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_MISSION_ITEM_INT >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_mission_item_int_t packet_in = { - 17.0,45.0,73.0,101.0,963498296,963498504,185.0,18691,18795,101,168,235,46,113,180 - }; - mavlink_mission_item_int_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.param1 = packet_in.param1; - packet1.param2 = packet_in.param2; - packet1.param3 = packet_in.param3; - packet1.param4 = packet_in.param4; - packet1.x = packet_in.x; - packet1.y = packet_in.y; - packet1.z = packet_in.z; - packet1.seq = packet_in.seq; - packet1.command = packet_in.command; - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - packet1.frame = packet_in.frame; - packet1.current = packet_in.current; - packet1.autocontinue = packet_in.autocontinue; - packet1.mission_type = packet_in.mission_type; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_MISSION_ITEM_INT_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_MISSION_ITEM_INT_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_mission_item_int_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_mission_item_int_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_mission_item_int_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.seq , packet1.frame , packet1.command , packet1.current , packet1.autocontinue , packet1.param1 , packet1.param2 , packet1.param3 , packet1.param4 , packet1.x , packet1.y , packet1.z , packet1.mission_type ); - mavlink_msg_mission_item_int_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_mission_item_int_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.seq , packet1.frame , packet1.command , packet1.current , packet1.autocontinue , packet1.param1 , packet1.param2 , packet1.param3 , packet1.param4 , packet1.x , packet1.y , packet1.z , packet1.mission_type ); - mavlink_msg_mission_item_int_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_VFR_HUD >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_vfr_hud_t packet_in = { - 17.0,45.0,73.0,101.0,18067,18171 - }; - mavlink_vfr_hud_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.airspeed = packet_in.airspeed; - packet1.groundspeed = packet_in.groundspeed; - packet1.alt = packet_in.alt; - packet1.climb = packet_in.climb; - packet1.heading = packet_in.heading; - packet1.throttle = packet_in.throttle; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_VFR_HUD_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_VFR_HUD_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_vfr_hud_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_vfr_hud_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_vfr_hud_pack(system_id, component_id, &msg , packet1.airspeed , packet1.groundspeed , packet1.heading , packet1.throttle , packet1.alt , packet1.climb ); - mavlink_msg_vfr_hud_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_vfr_hud_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.airspeed , packet1.groundspeed , packet1.heading , packet1.throttle , packet1.alt , packet1.climb ); - mavlink_msg_vfr_hud_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_COMMAND_INT >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_command_int_t packet_in = { - 17.0,45.0,73.0,101.0,963498296,963498504,185.0,18691,223,34,101,168,235 - }; - mavlink_command_int_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.param1 = packet_in.param1; - packet1.param2 = packet_in.param2; - packet1.param3 = packet_in.param3; - packet1.param4 = packet_in.param4; - packet1.x = packet_in.x; - packet1.y = packet_in.y; - packet1.z = packet_in.z; - packet1.command = packet_in.command; - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - packet1.frame = packet_in.frame; - packet1.current = packet_in.current; - packet1.autocontinue = packet_in.autocontinue; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_COMMAND_INT_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_COMMAND_INT_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_command_int_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_command_int_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_command_int_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.frame , packet1.command , packet1.current , packet1.autocontinue , packet1.param1 , packet1.param2 , packet1.param3 , packet1.param4 , packet1.x , packet1.y , packet1.z ); - mavlink_msg_command_int_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_command_int_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.frame , packet1.command , packet1.current , packet1.autocontinue , packet1.param1 , packet1.param2 , packet1.param3 , packet1.param4 , packet1.x , packet1.y , packet1.z ); - mavlink_msg_command_int_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_COMMAND_LONG >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_command_long_t packet_in = { - 17.0,45.0,73.0,101.0,129.0,157.0,185.0,18691,223,34,101 - }; - mavlink_command_long_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.param1 = packet_in.param1; - packet1.param2 = packet_in.param2; - packet1.param3 = packet_in.param3; - packet1.param4 = packet_in.param4; - packet1.param5 = packet_in.param5; - packet1.param6 = packet_in.param6; - packet1.param7 = packet_in.param7; - packet1.command = packet_in.command; - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - packet1.confirmation = packet_in.confirmation; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_COMMAND_LONG_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_COMMAND_LONG_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_command_long_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_command_long_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_command_long_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.command , packet1.confirmation , packet1.param1 , packet1.param2 , packet1.param3 , packet1.param4 , packet1.param5 , packet1.param6 , packet1.param7 ); - mavlink_msg_command_long_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_command_long_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.command , packet1.confirmation , packet1.param1 , packet1.param2 , packet1.param3 , packet1.param4 , packet1.param5 , packet1.param6 , packet1.param7 ); - mavlink_msg_command_long_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_COMMAND_ACK >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_command_ack_t packet_in = { - 17235,139,206,963497672,29,96 - }; - mavlink_command_ack_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.command = packet_in.command; - packet1.result = packet_in.result; - packet1.progress = packet_in.progress; - packet1.result_param2 = packet_in.result_param2; - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_COMMAND_ACK_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_COMMAND_ACK_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_command_ack_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_command_ack_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_command_ack_pack(system_id, component_id, &msg , packet1.command , packet1.result , packet1.progress , packet1.result_param2 , packet1.target_system , packet1.target_component ); - mavlink_msg_command_ack_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_command_ack_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.command , packet1.result , packet1.progress , packet1.result_param2 , packet1.target_system , packet1.target_component ); - mavlink_msg_command_ack_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_COMMAND_CANCEL >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_command_cancel_t packet_in = { - 17235,139,206 - }; - mavlink_command_cancel_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.command = packet_in.command; - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_COMMAND_CANCEL_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_COMMAND_CANCEL_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_command_cancel_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_command_cancel_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_command_cancel_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.command ); - mavlink_msg_command_cancel_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_command_cancel_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.command ); - mavlink_msg_command_cancel_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_MANUAL_SETPOINT >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_manual_setpoint_t packet_in = { - 963497464,45.0,73.0,101.0,129.0,65,132 - }; - mavlink_manual_setpoint_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_boot_ms = packet_in.time_boot_ms; - packet1.roll = packet_in.roll; - packet1.pitch = packet_in.pitch; - packet1.yaw = packet_in.yaw; - packet1.thrust = packet_in.thrust; - packet1.mode_switch = packet_in.mode_switch; - packet1.manual_override_switch = packet_in.manual_override_switch; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_MANUAL_SETPOINT_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_MANUAL_SETPOINT_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_manual_setpoint_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_manual_setpoint_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_manual_setpoint_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.roll , packet1.pitch , packet1.yaw , packet1.thrust , packet1.mode_switch , packet1.manual_override_switch ); - mavlink_msg_manual_setpoint_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_manual_setpoint_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.roll , packet1.pitch , packet1.yaw , packet1.thrust , packet1.mode_switch , packet1.manual_override_switch ); - mavlink_msg_manual_setpoint_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_SET_ATTITUDE_TARGET >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_set_attitude_target_t packet_in = { - 963497464,{ 45.0, 46.0, 47.0, 48.0 },157.0,185.0,213.0,241.0,113,180,247,{ 290.0, 291.0, 292.0 } - }; - mavlink_set_attitude_target_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_boot_ms = packet_in.time_boot_ms; - packet1.body_roll_rate = packet_in.body_roll_rate; - packet1.body_pitch_rate = packet_in.body_pitch_rate; - packet1.body_yaw_rate = packet_in.body_yaw_rate; - packet1.thrust = packet_in.thrust; - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - packet1.type_mask = packet_in.type_mask; - - mav_array_memcpy(packet1.q, packet_in.q, sizeof(float)*4); - mav_array_memcpy(packet1.thrust_body, packet_in.thrust_body, sizeof(float)*3); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_set_attitude_target_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_set_attitude_target_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_set_attitude_target_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.target_system , packet1.target_component , packet1.type_mask , packet1.q , packet1.body_roll_rate , packet1.body_pitch_rate , packet1.body_yaw_rate , packet1.thrust , packet1.thrust_body ); - mavlink_msg_set_attitude_target_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_set_attitude_target_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.target_system , packet1.target_component , packet1.type_mask , packet1.q , packet1.body_roll_rate , packet1.body_pitch_rate , packet1.body_yaw_rate , packet1.thrust , packet1.thrust_body ); - mavlink_msg_set_attitude_target_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_ATTITUDE_TARGET >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_attitude_target_t packet_in = { - 963497464,{ 45.0, 46.0, 47.0, 48.0 },157.0,185.0,213.0,241.0,113 - }; - mavlink_attitude_target_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_boot_ms = packet_in.time_boot_ms; - packet1.body_roll_rate = packet_in.body_roll_rate; - packet1.body_pitch_rate = packet_in.body_pitch_rate; - packet1.body_yaw_rate = packet_in.body_yaw_rate; - packet1.thrust = packet_in.thrust; - packet1.type_mask = packet_in.type_mask; - - mav_array_memcpy(packet1.q, packet_in.q, sizeof(float)*4); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_ATTITUDE_TARGET_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_ATTITUDE_TARGET_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_attitude_target_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_attitude_target_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_attitude_target_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.type_mask , packet1.q , packet1.body_roll_rate , packet1.body_pitch_rate , packet1.body_yaw_rate , packet1.thrust ); - mavlink_msg_attitude_target_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_attitude_target_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.type_mask , packet1.q , packet1.body_roll_rate , packet1.body_pitch_rate , packet1.body_yaw_rate , packet1.thrust ); - mavlink_msg_attitude_target_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_set_position_target_local_ned_t packet_in = { - 963497464,45.0,73.0,101.0,129.0,157.0,185.0,213.0,241.0,269.0,297.0,325.0,19731,27,94,161 - }; - mavlink_set_position_target_local_ned_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_boot_ms = packet_in.time_boot_ms; - packet1.x = packet_in.x; - packet1.y = packet_in.y; - packet1.z = packet_in.z; - packet1.vx = packet_in.vx; - packet1.vy = packet_in.vy; - packet1.vz = packet_in.vz; - packet1.afx = packet_in.afx; - packet1.afy = packet_in.afy; - packet1.afz = packet_in.afz; - packet1.yaw = packet_in.yaw; - packet1.yaw_rate = packet_in.yaw_rate; - packet1.type_mask = packet_in.type_mask; - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - packet1.coordinate_frame = packet_in.coordinate_frame; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_set_position_target_local_ned_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_set_position_target_local_ned_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_set_position_target_local_ned_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.target_system , packet1.target_component , packet1.coordinate_frame , packet1.type_mask , packet1.x , packet1.y , packet1.z , packet1.vx , packet1.vy , packet1.vz , packet1.afx , packet1.afy , packet1.afz , packet1.yaw , packet1.yaw_rate ); - mavlink_msg_set_position_target_local_ned_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_set_position_target_local_ned_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.target_system , packet1.target_component , packet1.coordinate_frame , packet1.type_mask , packet1.x , packet1.y , packet1.z , packet1.vx , packet1.vy , packet1.vz , packet1.afx , packet1.afy , packet1.afz , packet1.yaw , packet1.yaw_rate ); - mavlink_msg_set_position_target_local_ned_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_position_target_local_ned_t packet_in = { - 963497464,45.0,73.0,101.0,129.0,157.0,185.0,213.0,241.0,269.0,297.0,325.0,19731,27 - }; - mavlink_position_target_local_ned_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_boot_ms = packet_in.time_boot_ms; - packet1.x = packet_in.x; - packet1.y = packet_in.y; - packet1.z = packet_in.z; - packet1.vx = packet_in.vx; - packet1.vy = packet_in.vy; - packet1.vz = packet_in.vz; - packet1.afx = packet_in.afx; - packet1.afy = packet_in.afy; - packet1.afz = packet_in.afz; - packet1.yaw = packet_in.yaw; - packet1.yaw_rate = packet_in.yaw_rate; - packet1.type_mask = packet_in.type_mask; - packet1.coordinate_frame = packet_in.coordinate_frame; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_position_target_local_ned_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_position_target_local_ned_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_position_target_local_ned_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.coordinate_frame , packet1.type_mask , packet1.x , packet1.y , packet1.z , packet1.vx , packet1.vy , packet1.vz , packet1.afx , packet1.afy , packet1.afz , packet1.yaw , packet1.yaw_rate ); - mavlink_msg_position_target_local_ned_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_position_target_local_ned_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.coordinate_frame , packet1.type_mask , packet1.x , packet1.y , packet1.z , packet1.vx , packet1.vy , packet1.vz , packet1.afx , packet1.afy , packet1.afz , packet1.yaw , packet1.yaw_rate ); - mavlink_msg_position_target_local_ned_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_set_position_target_global_int_t packet_in = { - 963497464,963497672,963497880,101.0,129.0,157.0,185.0,213.0,241.0,269.0,297.0,325.0,19731,27,94,161 - }; - mavlink_set_position_target_global_int_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_boot_ms = packet_in.time_boot_ms; - packet1.lat_int = packet_in.lat_int; - packet1.lon_int = packet_in.lon_int; - packet1.alt = packet_in.alt; - packet1.vx = packet_in.vx; - packet1.vy = packet_in.vy; - packet1.vz = packet_in.vz; - packet1.afx = packet_in.afx; - packet1.afy = packet_in.afy; - packet1.afz = packet_in.afz; - packet1.yaw = packet_in.yaw; - packet1.yaw_rate = packet_in.yaw_rate; - packet1.type_mask = packet_in.type_mask; - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - packet1.coordinate_frame = packet_in.coordinate_frame; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_set_position_target_global_int_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_set_position_target_global_int_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_set_position_target_global_int_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.target_system , packet1.target_component , packet1.coordinate_frame , packet1.type_mask , packet1.lat_int , packet1.lon_int , packet1.alt , packet1.vx , packet1.vy , packet1.vz , packet1.afx , packet1.afy , packet1.afz , packet1.yaw , packet1.yaw_rate ); - mavlink_msg_set_position_target_global_int_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_set_position_target_global_int_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.target_system , packet1.target_component , packet1.coordinate_frame , packet1.type_mask , packet1.lat_int , packet1.lon_int , packet1.alt , packet1.vx , packet1.vy , packet1.vz , packet1.afx , packet1.afy , packet1.afz , packet1.yaw , packet1.yaw_rate ); - mavlink_msg_set_position_target_global_int_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_position_target_global_int_t packet_in = { - 963497464,963497672,963497880,101.0,129.0,157.0,185.0,213.0,241.0,269.0,297.0,325.0,19731,27 - }; - mavlink_position_target_global_int_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_boot_ms = packet_in.time_boot_ms; - packet1.lat_int = packet_in.lat_int; - packet1.lon_int = packet_in.lon_int; - packet1.alt = packet_in.alt; - packet1.vx = packet_in.vx; - packet1.vy = packet_in.vy; - packet1.vz = packet_in.vz; - packet1.afx = packet_in.afx; - packet1.afy = packet_in.afy; - packet1.afz = packet_in.afz; - packet1.yaw = packet_in.yaw; - packet1.yaw_rate = packet_in.yaw_rate; - packet1.type_mask = packet_in.type_mask; - packet1.coordinate_frame = packet_in.coordinate_frame; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_position_target_global_int_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_position_target_global_int_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_position_target_global_int_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.coordinate_frame , packet1.type_mask , packet1.lat_int , packet1.lon_int , packet1.alt , packet1.vx , packet1.vy , packet1.vz , packet1.afx , packet1.afy , packet1.afz , packet1.yaw , packet1.yaw_rate ); - mavlink_msg_position_target_global_int_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_position_target_global_int_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.coordinate_frame , packet1.type_mask , packet1.lat_int , packet1.lon_int , packet1.alt , packet1.vx , packet1.vy , packet1.vz , packet1.afx , packet1.afy , packet1.afz , packet1.yaw , packet1.yaw_rate ); - mavlink_msg_position_target_global_int_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_local_position_ned_system_global_offset_t packet_in = { - 963497464,45.0,73.0,101.0,129.0,157.0,185.0 - }; - mavlink_local_position_ned_system_global_offset_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_boot_ms = packet_in.time_boot_ms; - packet1.x = packet_in.x; - packet1.y = packet_in.y; - packet1.z = packet_in.z; - packet1.roll = packet_in.roll; - packet1.pitch = packet_in.pitch; - packet1.yaw = packet_in.yaw; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_local_position_ned_system_global_offset_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_local_position_ned_system_global_offset_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_local_position_ned_system_global_offset_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.x , packet1.y , packet1.z , packet1.roll , packet1.pitch , packet1.yaw ); - mavlink_msg_local_position_ned_system_global_offset_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_local_position_ned_system_global_offset_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.x , packet1.y , packet1.z , packet1.roll , packet1.pitch , packet1.yaw ); - mavlink_msg_local_position_ned_system_global_offset_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_HIL_STATE >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_hil_state_t packet_in = { - 93372036854775807ULL,73.0,101.0,129.0,157.0,185.0,213.0,963499128,963499336,963499544,19523,19627,19731,19835,19939,20043 - }; - mavlink_hil_state_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_usec = packet_in.time_usec; - packet1.roll = packet_in.roll; - packet1.pitch = packet_in.pitch; - packet1.yaw = packet_in.yaw; - packet1.rollspeed = packet_in.rollspeed; - packet1.pitchspeed = packet_in.pitchspeed; - packet1.yawspeed = packet_in.yawspeed; - packet1.lat = packet_in.lat; - packet1.lon = packet_in.lon; - packet1.alt = packet_in.alt; - packet1.vx = packet_in.vx; - packet1.vy = packet_in.vy; - packet1.vz = packet_in.vz; - packet1.xacc = packet_in.xacc; - packet1.yacc = packet_in.yacc; - packet1.zacc = packet_in.zacc; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_HIL_STATE_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_HIL_STATE_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_hil_state_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_hil_state_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_hil_state_pack(system_id, component_id, &msg , packet1.time_usec , packet1.roll , packet1.pitch , packet1.yaw , packet1.rollspeed , packet1.pitchspeed , packet1.yawspeed , packet1.lat , packet1.lon , packet1.alt , packet1.vx , packet1.vy , packet1.vz , packet1.xacc , packet1.yacc , packet1.zacc ); - mavlink_msg_hil_state_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_hil_state_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.roll , packet1.pitch , packet1.yaw , packet1.rollspeed , packet1.pitchspeed , packet1.yawspeed , packet1.lat , packet1.lon , packet1.alt , packet1.vx , packet1.vy , packet1.vz , packet1.xacc , packet1.yacc , packet1.zacc ); - mavlink_msg_hil_state_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_HIL_CONTROLS >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_hil_controls_t packet_in = { - 93372036854775807ULL,73.0,101.0,129.0,157.0,185.0,213.0,241.0,269.0,125,192 - }; - mavlink_hil_controls_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_usec = packet_in.time_usec; - packet1.roll_ailerons = packet_in.roll_ailerons; - packet1.pitch_elevator = packet_in.pitch_elevator; - packet1.yaw_rudder = packet_in.yaw_rudder; - packet1.throttle = packet_in.throttle; - packet1.aux1 = packet_in.aux1; - packet1.aux2 = packet_in.aux2; - packet1.aux3 = packet_in.aux3; - packet1.aux4 = packet_in.aux4; - packet1.mode = packet_in.mode; - packet1.nav_mode = packet_in.nav_mode; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_HIL_CONTROLS_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_HIL_CONTROLS_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_hil_controls_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_hil_controls_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_hil_controls_pack(system_id, component_id, &msg , packet1.time_usec , packet1.roll_ailerons , packet1.pitch_elevator , packet1.yaw_rudder , packet1.throttle , packet1.aux1 , packet1.aux2 , packet1.aux3 , packet1.aux4 , packet1.mode , packet1.nav_mode ); - mavlink_msg_hil_controls_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_hil_controls_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.roll_ailerons , packet1.pitch_elevator , packet1.yaw_rudder , packet1.throttle , packet1.aux1 , packet1.aux2 , packet1.aux3 , packet1.aux4 , packet1.mode , packet1.nav_mode ); - mavlink_msg_hil_controls_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_hil_rc_inputs_raw_t packet_in = { - 93372036854775807ULL,17651,17755,17859,17963,18067,18171,18275,18379,18483,18587,18691,18795,101 - }; - mavlink_hil_rc_inputs_raw_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_usec = packet_in.time_usec; - packet1.chan1_raw = packet_in.chan1_raw; - packet1.chan2_raw = packet_in.chan2_raw; - packet1.chan3_raw = packet_in.chan3_raw; - packet1.chan4_raw = packet_in.chan4_raw; - packet1.chan5_raw = packet_in.chan5_raw; - packet1.chan6_raw = packet_in.chan6_raw; - packet1.chan7_raw = packet_in.chan7_raw; - packet1.chan8_raw = packet_in.chan8_raw; - packet1.chan9_raw = packet_in.chan9_raw; - packet1.chan10_raw = packet_in.chan10_raw; - packet1.chan11_raw = packet_in.chan11_raw; - packet1.chan12_raw = packet_in.chan12_raw; - packet1.rssi = packet_in.rssi; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_hil_rc_inputs_raw_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_hil_rc_inputs_raw_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_hil_rc_inputs_raw_pack(system_id, component_id, &msg , packet1.time_usec , packet1.chan1_raw , packet1.chan2_raw , packet1.chan3_raw , packet1.chan4_raw , packet1.chan5_raw , packet1.chan6_raw , packet1.chan7_raw , packet1.chan8_raw , packet1.chan9_raw , packet1.chan10_raw , packet1.chan11_raw , packet1.chan12_raw , packet1.rssi ); - mavlink_msg_hil_rc_inputs_raw_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_hil_rc_inputs_raw_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.chan1_raw , packet1.chan2_raw , packet1.chan3_raw , packet1.chan4_raw , packet1.chan5_raw , packet1.chan6_raw , packet1.chan7_raw , packet1.chan8_raw , packet1.chan9_raw , packet1.chan10_raw , packet1.chan11_raw , packet1.chan12_raw , packet1.rssi ); - mavlink_msg_hil_rc_inputs_raw_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_hil_actuator_controls_t packet_in = { - 93372036854775807ULL,93372036854776311ULL,{ 129.0, 130.0, 131.0, 132.0, 133.0, 134.0, 135.0, 136.0, 137.0, 138.0, 139.0, 140.0, 141.0, 142.0, 143.0, 144.0 },245 - }; - mavlink_hil_actuator_controls_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_usec = packet_in.time_usec; - packet1.flags = packet_in.flags; - packet1.mode = packet_in.mode; - - mav_array_memcpy(packet1.controls, packet_in.controls, sizeof(float)*16); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_hil_actuator_controls_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_hil_actuator_controls_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_hil_actuator_controls_pack(system_id, component_id, &msg , packet1.time_usec , packet1.controls , packet1.mode , packet1.flags ); - mavlink_msg_hil_actuator_controls_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_hil_actuator_controls_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.controls , packet1.mode , packet1.flags ); - mavlink_msg_hil_actuator_controls_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_OPTICAL_FLOW >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_optical_flow_t packet_in = { - 93372036854775807ULL,73.0,101.0,129.0,18275,18379,77,144,199.0,227.0 - }; - mavlink_optical_flow_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_usec = packet_in.time_usec; - packet1.flow_comp_m_x = packet_in.flow_comp_m_x; - packet1.flow_comp_m_y = packet_in.flow_comp_m_y; - packet1.ground_distance = packet_in.ground_distance; - packet1.flow_x = packet_in.flow_x; - packet1.flow_y = packet_in.flow_y; - packet1.sensor_id = packet_in.sensor_id; - packet1.quality = packet_in.quality; - packet1.flow_rate_x = packet_in.flow_rate_x; - packet1.flow_rate_y = packet_in.flow_rate_y; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_OPTICAL_FLOW_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_OPTICAL_FLOW_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_optical_flow_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_optical_flow_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_optical_flow_pack(system_id, component_id, &msg , packet1.time_usec , packet1.sensor_id , packet1.flow_x , packet1.flow_y , packet1.flow_comp_m_x , packet1.flow_comp_m_y , packet1.quality , packet1.ground_distance , packet1.flow_rate_x , packet1.flow_rate_y ); - mavlink_msg_optical_flow_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_optical_flow_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.sensor_id , packet1.flow_x , packet1.flow_y , packet1.flow_comp_m_x , packet1.flow_comp_m_y , packet1.quality , packet1.ground_distance , packet1.flow_rate_x , packet1.flow_rate_y ); - mavlink_msg_optical_flow_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_global_vision_position_estimate_t packet_in = { - 93372036854775807ULL,73.0,101.0,129.0,157.0,185.0,213.0,{ 241.0, 242.0, 243.0, 244.0, 245.0, 246.0, 247.0, 248.0, 249.0, 250.0, 251.0, 252.0, 253.0, 254.0, 255.0, 256.0, 257.0, 258.0, 259.0, 260.0, 261.0 },97 - }; - mavlink_global_vision_position_estimate_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.usec = packet_in.usec; - packet1.x = packet_in.x; - packet1.y = packet_in.y; - packet1.z = packet_in.z; - packet1.roll = packet_in.roll; - packet1.pitch = packet_in.pitch; - packet1.yaw = packet_in.yaw; - packet1.reset_counter = packet_in.reset_counter; - - mav_array_memcpy(packet1.covariance, packet_in.covariance, sizeof(float)*21); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_global_vision_position_estimate_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_global_vision_position_estimate_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_global_vision_position_estimate_pack(system_id, component_id, &msg , packet1.usec , packet1.x , packet1.y , packet1.z , packet1.roll , packet1.pitch , packet1.yaw , packet1.covariance , packet1.reset_counter ); - mavlink_msg_global_vision_position_estimate_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_global_vision_position_estimate_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.usec , packet1.x , packet1.y , packet1.z , packet1.roll , packet1.pitch , packet1.yaw , packet1.covariance , packet1.reset_counter ); - mavlink_msg_global_vision_position_estimate_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_vision_position_estimate_t packet_in = { - 93372036854775807ULL,73.0,101.0,129.0,157.0,185.0,213.0,{ 241.0, 242.0, 243.0, 244.0, 245.0, 246.0, 247.0, 248.0, 249.0, 250.0, 251.0, 252.0, 253.0, 254.0, 255.0, 256.0, 257.0, 258.0, 259.0, 260.0, 261.0 },97 - }; - mavlink_vision_position_estimate_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.usec = packet_in.usec; - packet1.x = packet_in.x; - packet1.y = packet_in.y; - packet1.z = packet_in.z; - packet1.roll = packet_in.roll; - packet1.pitch = packet_in.pitch; - packet1.yaw = packet_in.yaw; - packet1.reset_counter = packet_in.reset_counter; - - mav_array_memcpy(packet1.covariance, packet_in.covariance, sizeof(float)*21); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_vision_position_estimate_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_vision_position_estimate_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_vision_position_estimate_pack(system_id, component_id, &msg , packet1.usec , packet1.x , packet1.y , packet1.z , packet1.roll , packet1.pitch , packet1.yaw , packet1.covariance , packet1.reset_counter ); - mavlink_msg_vision_position_estimate_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_vision_position_estimate_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.usec , packet1.x , packet1.y , packet1.z , packet1.roll , packet1.pitch , packet1.yaw , packet1.covariance , packet1.reset_counter ); - mavlink_msg_vision_position_estimate_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_vision_speed_estimate_t packet_in = { - 93372036854775807ULL,73.0,101.0,129.0,{ 157.0, 158.0, 159.0, 160.0, 161.0, 162.0, 163.0, 164.0, 165.0 },173 - }; - mavlink_vision_speed_estimate_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.usec = packet_in.usec; - packet1.x = packet_in.x; - packet1.y = packet_in.y; - packet1.z = packet_in.z; - packet1.reset_counter = packet_in.reset_counter; - - mav_array_memcpy(packet1.covariance, packet_in.covariance, sizeof(float)*9); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_vision_speed_estimate_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_vision_speed_estimate_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_vision_speed_estimate_pack(system_id, component_id, &msg , packet1.usec , packet1.x , packet1.y , packet1.z , packet1.covariance , packet1.reset_counter ); - mavlink_msg_vision_speed_estimate_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_vision_speed_estimate_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.usec , packet1.x , packet1.y , packet1.z , packet1.covariance , packet1.reset_counter ); - mavlink_msg_vision_speed_estimate_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_vicon_position_estimate_t packet_in = { - 93372036854775807ULL,73.0,101.0,129.0,157.0,185.0,213.0,{ 241.0, 242.0, 243.0, 244.0, 245.0, 246.0, 247.0, 248.0, 249.0, 250.0, 251.0, 252.0, 253.0, 254.0, 255.0, 256.0, 257.0, 258.0, 259.0, 260.0, 261.0 } - }; - mavlink_vicon_position_estimate_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.usec = packet_in.usec; - packet1.x = packet_in.x; - packet1.y = packet_in.y; - packet1.z = packet_in.z; - packet1.roll = packet_in.roll; - packet1.pitch = packet_in.pitch; - packet1.yaw = packet_in.yaw; - - mav_array_memcpy(packet1.covariance, packet_in.covariance, sizeof(float)*21); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_vicon_position_estimate_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_vicon_position_estimate_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_vicon_position_estimate_pack(system_id, component_id, &msg , packet1.usec , packet1.x , packet1.y , packet1.z , packet1.roll , packet1.pitch , packet1.yaw , packet1.covariance ); - mavlink_msg_vicon_position_estimate_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_vicon_position_estimate_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.usec , packet1.x , packet1.y , packet1.z , packet1.roll , packet1.pitch , packet1.yaw , packet1.covariance ); - mavlink_msg_vicon_position_estimate_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_HIGHRES_IMU >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_highres_imu_t packet_in = { - 93372036854775807ULL,73.0,101.0,129.0,157.0,185.0,213.0,241.0,269.0,297.0,325.0,353.0,381.0,409.0,20355,63 - }; - mavlink_highres_imu_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_usec = packet_in.time_usec; - packet1.xacc = packet_in.xacc; - packet1.yacc = packet_in.yacc; - packet1.zacc = packet_in.zacc; - packet1.xgyro = packet_in.xgyro; - packet1.ygyro = packet_in.ygyro; - packet1.zgyro = packet_in.zgyro; - packet1.xmag = packet_in.xmag; - packet1.ymag = packet_in.ymag; - packet1.zmag = packet_in.zmag; - packet1.abs_pressure = packet_in.abs_pressure; - packet1.diff_pressure = packet_in.diff_pressure; - packet1.pressure_alt = packet_in.pressure_alt; - packet1.temperature = packet_in.temperature; - packet1.fields_updated = packet_in.fields_updated; - packet1.id = packet_in.id; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_HIGHRES_IMU_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_HIGHRES_IMU_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_highres_imu_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_highres_imu_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_highres_imu_pack(system_id, component_id, &msg , packet1.time_usec , packet1.xacc , packet1.yacc , packet1.zacc , packet1.xgyro , packet1.ygyro , packet1.zgyro , packet1.xmag , packet1.ymag , packet1.zmag , packet1.abs_pressure , packet1.diff_pressure , packet1.pressure_alt , packet1.temperature , packet1.fields_updated , packet1.id ); - mavlink_msg_highres_imu_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_highres_imu_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.xacc , packet1.yacc , packet1.zacc , packet1.xgyro , packet1.ygyro , packet1.zgyro , packet1.xmag , packet1.ymag , packet1.zmag , packet1.abs_pressure , packet1.diff_pressure , packet1.pressure_alt , packet1.temperature , packet1.fields_updated , packet1.id ); - mavlink_msg_highres_imu_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_OPTICAL_FLOW_RAD >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_optical_flow_rad_t packet_in = { - 93372036854775807ULL,963497880,101.0,129.0,157.0,185.0,213.0,963499128,269.0,19315,3,70 - }; - mavlink_optical_flow_rad_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_usec = packet_in.time_usec; - packet1.integration_time_us = packet_in.integration_time_us; - packet1.integrated_x = packet_in.integrated_x; - packet1.integrated_y = packet_in.integrated_y; - packet1.integrated_xgyro = packet_in.integrated_xgyro; - packet1.integrated_ygyro = packet_in.integrated_ygyro; - packet1.integrated_zgyro = packet_in.integrated_zgyro; - packet1.time_delta_distance_us = packet_in.time_delta_distance_us; - packet1.distance = packet_in.distance; - packet1.temperature = packet_in.temperature; - packet1.sensor_id = packet_in.sensor_id; - packet1.quality = packet_in.quality; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_optical_flow_rad_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_optical_flow_rad_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_optical_flow_rad_pack(system_id, component_id, &msg , packet1.time_usec , packet1.sensor_id , packet1.integration_time_us , packet1.integrated_x , packet1.integrated_y , packet1.integrated_xgyro , packet1.integrated_ygyro , packet1.integrated_zgyro , packet1.temperature , packet1.quality , packet1.time_delta_distance_us , packet1.distance ); - mavlink_msg_optical_flow_rad_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_optical_flow_rad_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.sensor_id , packet1.integration_time_us , packet1.integrated_x , packet1.integrated_y , packet1.integrated_xgyro , packet1.integrated_ygyro , packet1.integrated_zgyro , packet1.temperature , packet1.quality , packet1.time_delta_distance_us , packet1.distance ); - mavlink_msg_optical_flow_rad_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_HIL_SENSOR >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_hil_sensor_t packet_in = { - 93372036854775807ULL,73.0,101.0,129.0,157.0,185.0,213.0,241.0,269.0,297.0,325.0,353.0,381.0,409.0,963500584,197 - }; - mavlink_hil_sensor_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_usec = packet_in.time_usec; - packet1.xacc = packet_in.xacc; - packet1.yacc = packet_in.yacc; - packet1.zacc = packet_in.zacc; - packet1.xgyro = packet_in.xgyro; - packet1.ygyro = packet_in.ygyro; - packet1.zgyro = packet_in.zgyro; - packet1.xmag = packet_in.xmag; - packet1.ymag = packet_in.ymag; - packet1.zmag = packet_in.zmag; - packet1.abs_pressure = packet_in.abs_pressure; - packet1.diff_pressure = packet_in.diff_pressure; - packet1.pressure_alt = packet_in.pressure_alt; - packet1.temperature = packet_in.temperature; - packet1.fields_updated = packet_in.fields_updated; - packet1.id = packet_in.id; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_HIL_SENSOR_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_HIL_SENSOR_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_hil_sensor_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_hil_sensor_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_hil_sensor_pack(system_id, component_id, &msg , packet1.time_usec , packet1.xacc , packet1.yacc , packet1.zacc , packet1.xgyro , packet1.ygyro , packet1.zgyro , packet1.xmag , packet1.ymag , packet1.zmag , packet1.abs_pressure , packet1.diff_pressure , packet1.pressure_alt , packet1.temperature , packet1.fields_updated , packet1.id ); - mavlink_msg_hil_sensor_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_hil_sensor_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.xacc , packet1.yacc , packet1.zacc , packet1.xgyro , packet1.ygyro , packet1.zgyro , packet1.xmag , packet1.ymag , packet1.zmag , packet1.abs_pressure , packet1.diff_pressure , packet1.pressure_alt , packet1.temperature , packet1.fields_updated , packet1.id ); - mavlink_msg_hil_sensor_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_SIM_STATE >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_sim_state_t packet_in = { - 17.0,45.0,73.0,101.0,129.0,157.0,185.0,213.0,241.0,269.0,297.0,325.0,353.0,381.0,409.0,437.0,465.0,493.0,521.0,549.0,577.0,963501832,963502040 - }; - mavlink_sim_state_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.q1 = packet_in.q1; - packet1.q2 = packet_in.q2; - packet1.q3 = packet_in.q3; - packet1.q4 = packet_in.q4; - packet1.roll = packet_in.roll; - packet1.pitch = packet_in.pitch; - packet1.yaw = packet_in.yaw; - packet1.xacc = packet_in.xacc; - packet1.yacc = packet_in.yacc; - packet1.zacc = packet_in.zacc; - packet1.xgyro = packet_in.xgyro; - packet1.ygyro = packet_in.ygyro; - packet1.zgyro = packet_in.zgyro; - packet1.lat = packet_in.lat; - packet1.lon = packet_in.lon; - packet1.alt = packet_in.alt; - packet1.std_dev_horz = packet_in.std_dev_horz; - packet1.std_dev_vert = packet_in.std_dev_vert; - packet1.vn = packet_in.vn; - packet1.ve = packet_in.ve; - packet1.vd = packet_in.vd; - packet1.lat_int = packet_in.lat_int; - packet1.lon_int = packet_in.lon_int; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_SIM_STATE_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SIM_STATE_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_sim_state_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_sim_state_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_sim_state_pack(system_id, component_id, &msg , packet1.q1 , packet1.q2 , packet1.q3 , packet1.q4 , packet1.roll , packet1.pitch , packet1.yaw , packet1.xacc , packet1.yacc , packet1.zacc , packet1.xgyro , packet1.ygyro , packet1.zgyro , packet1.lat , packet1.lon , packet1.alt , packet1.std_dev_horz , packet1.std_dev_vert , packet1.vn , packet1.ve , packet1.vd , packet1.lat_int , packet1.lon_int ); - mavlink_msg_sim_state_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_sim_state_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.q1 , packet1.q2 , packet1.q3 , packet1.q4 , packet1.roll , packet1.pitch , packet1.yaw , packet1.xacc , packet1.yacc , packet1.zacc , packet1.xgyro , packet1.ygyro , packet1.zgyro , packet1.lat , packet1.lon , packet1.alt , packet1.std_dev_horz , packet1.std_dev_vert , packet1.vn , packet1.ve , packet1.vd , packet1.lat_int , packet1.lon_int ); - mavlink_msg_sim_state_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_RADIO_STATUS >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_radio_status_t packet_in = { - 17235,17339,17,84,151,218,29 - }; - mavlink_radio_status_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.rxerrors = packet_in.rxerrors; - packet1.fixed = packet_in.fixed; - packet1.rssi = packet_in.rssi; - packet1.remrssi = packet_in.remrssi; - packet1.txbuf = packet_in.txbuf; - packet1.noise = packet_in.noise; - packet1.remnoise = packet_in.remnoise; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_RADIO_STATUS_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_RADIO_STATUS_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_radio_status_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_radio_status_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_radio_status_pack(system_id, component_id, &msg , packet1.rssi , packet1.remrssi , packet1.txbuf , packet1.noise , packet1.remnoise , packet1.rxerrors , packet1.fixed ); - mavlink_msg_radio_status_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_radio_status_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.rssi , packet1.remrssi , packet1.txbuf , packet1.noise , packet1.remnoise , packet1.rxerrors , packet1.fixed ); - mavlink_msg_radio_status_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_file_transfer_protocol_t packet_in = { - 5,72,139,{ 206, 207, 208, 209, 210, 211, 212, 213, 214, 215, 216, 217, 218, 219, 220, 221, 222, 223, 224, 225, 226, 227, 228, 229, 230, 231, 232, 233, 234, 235, 236, 237, 238, 239, 240, 241, 242, 243, 244, 245, 246, 247, 248, 249, 250, 251, 252, 253, 254, 255, 0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31, 32, 33, 34, 35, 36, 37, 38, 39, 40, 41, 42, 43, 44, 45, 46, 47, 48, 49, 50, 51, 52, 53, 54, 55, 56, 57, 58, 59, 60, 61, 62, 63, 64, 65, 66, 67, 68, 69, 70, 71, 72, 73, 74, 75, 76, 77, 78, 79, 80, 81, 82, 83, 84, 85, 86, 87, 88, 89, 90, 91, 92, 93, 94, 95, 96, 97, 98, 99, 100, 101, 102, 103, 104, 105, 106, 107, 108, 109, 110, 111, 112, 113, 114, 115, 116, 117, 118, 119, 120, 121, 122, 123, 124, 125, 126, 127, 128, 129, 130, 131, 132, 133, 134, 135, 136, 137, 138, 139, 140, 141, 142, 143, 144, 145, 146, 147, 148, 149, 150, 151, 152, 153, 154, 155, 156, 157, 158, 159, 160, 161, 162, 163, 164, 165, 166, 167, 168, 169, 170, 171, 172, 173, 174, 175, 176, 177, 178, 179, 180, 181, 182, 183, 184, 185, 186, 187, 188, 189, 190, 191, 192, 193, 194, 195, 196, 197, 198, 199, 200 } - }; - mavlink_file_transfer_protocol_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.target_network = packet_in.target_network; - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - - mav_array_memcpy(packet1.payload, packet_in.payload, sizeof(uint8_t)*251); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_file_transfer_protocol_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_file_transfer_protocol_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_file_transfer_protocol_pack(system_id, component_id, &msg , packet1.target_network , packet1.target_system , packet1.target_component , packet1.payload ); - mavlink_msg_file_transfer_protocol_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_file_transfer_protocol_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_network , packet1.target_system , packet1.target_component , packet1.payload ); - mavlink_msg_file_transfer_protocol_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_TIMESYNC >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_timesync_t packet_in = { - 93372036854775807LL,93372036854776311LL,53,120 - }; - mavlink_timesync_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.tc1 = packet_in.tc1; - packet1.ts1 = packet_in.ts1; - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_TIMESYNC_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_TIMESYNC_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_timesync_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_timesync_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_timesync_pack(system_id, component_id, &msg , packet1.tc1 , packet1.ts1 , packet1.target_system , packet1.target_component ); - mavlink_msg_timesync_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_timesync_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.tc1 , packet1.ts1 , packet1.target_system , packet1.target_component ); - mavlink_msg_timesync_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_CAMERA_TRIGGER >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_camera_trigger_t packet_in = { - 93372036854775807ULL,963497880 - }; - mavlink_camera_trigger_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_usec = packet_in.time_usec; - packet1.seq = packet_in.seq; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_CAMERA_TRIGGER_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_CAMERA_TRIGGER_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_camera_trigger_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_camera_trigger_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_camera_trigger_pack(system_id, component_id, &msg , packet1.time_usec , packet1.seq ); - mavlink_msg_camera_trigger_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_camera_trigger_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.seq ); - mavlink_msg_camera_trigger_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_HIL_GPS >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_hil_gps_t packet_in = { - 93372036854775807ULL,963497880,963498088,963498296,18275,18379,18483,18587,18691,18795,18899,235,46,113,19159 - }; - mavlink_hil_gps_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_usec = packet_in.time_usec; - packet1.lat = packet_in.lat; - packet1.lon = packet_in.lon; - packet1.alt = packet_in.alt; - packet1.eph = packet_in.eph; - packet1.epv = packet_in.epv; - packet1.vel = packet_in.vel; - packet1.vn = packet_in.vn; - packet1.ve = packet_in.ve; - packet1.vd = packet_in.vd; - packet1.cog = packet_in.cog; - packet1.fix_type = packet_in.fix_type; - packet1.satellites_visible = packet_in.satellites_visible; - packet1.id = packet_in.id; - packet1.yaw = packet_in.yaw; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_HIL_GPS_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_HIL_GPS_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_hil_gps_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_hil_gps_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_hil_gps_pack(system_id, component_id, &msg , packet1.time_usec , packet1.fix_type , packet1.lat , packet1.lon , packet1.alt , packet1.eph , packet1.epv , packet1.vel , packet1.vn , packet1.ve , packet1.vd , packet1.cog , packet1.satellites_visible , packet1.id , packet1.yaw ); - mavlink_msg_hil_gps_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_hil_gps_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.fix_type , packet1.lat , packet1.lon , packet1.alt , packet1.eph , packet1.epv , packet1.vel , packet1.vn , packet1.ve , packet1.vd , packet1.cog , packet1.satellites_visible , packet1.id , packet1.yaw ); - mavlink_msg_hil_gps_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_HIL_OPTICAL_FLOW >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_hil_optical_flow_t packet_in = { - 93372036854775807ULL,963497880,101.0,129.0,157.0,185.0,213.0,963499128,269.0,19315,3,70 - }; - mavlink_hil_optical_flow_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_usec = packet_in.time_usec; - packet1.integration_time_us = packet_in.integration_time_us; - packet1.integrated_x = packet_in.integrated_x; - packet1.integrated_y = packet_in.integrated_y; - packet1.integrated_xgyro = packet_in.integrated_xgyro; - packet1.integrated_ygyro = packet_in.integrated_ygyro; - packet1.integrated_zgyro = packet_in.integrated_zgyro; - packet1.time_delta_distance_us = packet_in.time_delta_distance_us; - packet1.distance = packet_in.distance; - packet1.temperature = packet_in.temperature; - packet1.sensor_id = packet_in.sensor_id; - packet1.quality = packet_in.quality; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_hil_optical_flow_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_hil_optical_flow_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_hil_optical_flow_pack(system_id, component_id, &msg , packet1.time_usec , packet1.sensor_id , packet1.integration_time_us , packet1.integrated_x , packet1.integrated_y , packet1.integrated_xgyro , packet1.integrated_ygyro , packet1.integrated_zgyro , packet1.temperature , packet1.quality , packet1.time_delta_distance_us , packet1.distance ); - mavlink_msg_hil_optical_flow_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_hil_optical_flow_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.sensor_id , packet1.integration_time_us , packet1.integrated_x , packet1.integrated_y , packet1.integrated_xgyro , packet1.integrated_ygyro , packet1.integrated_zgyro , packet1.temperature , packet1.quality , packet1.time_delta_distance_us , packet1.distance ); - mavlink_msg_hil_optical_flow_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_HIL_STATE_QUATERNION >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_hil_state_quaternion_t packet_in = { - 93372036854775807ULL,{ 73.0, 74.0, 75.0, 76.0 },185.0,213.0,241.0,963499336,963499544,963499752,19731,19835,19939,20043,20147,20251,20355,20459 - }; - mavlink_hil_state_quaternion_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_usec = packet_in.time_usec; - packet1.rollspeed = packet_in.rollspeed; - packet1.pitchspeed = packet_in.pitchspeed; - packet1.yawspeed = packet_in.yawspeed; - packet1.lat = packet_in.lat; - packet1.lon = packet_in.lon; - packet1.alt = packet_in.alt; - packet1.vx = packet_in.vx; - packet1.vy = packet_in.vy; - packet1.vz = packet_in.vz; - packet1.ind_airspeed = packet_in.ind_airspeed; - packet1.true_airspeed = packet_in.true_airspeed; - packet1.xacc = packet_in.xacc; - packet1.yacc = packet_in.yacc; - packet1.zacc = packet_in.zacc; - - mav_array_memcpy(packet1.attitude_quaternion, packet_in.attitude_quaternion, sizeof(float)*4); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_HIL_STATE_QUATERNION_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_HIL_STATE_QUATERNION_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_hil_state_quaternion_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_hil_state_quaternion_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_hil_state_quaternion_pack(system_id, component_id, &msg , packet1.time_usec , packet1.attitude_quaternion , packet1.rollspeed , packet1.pitchspeed , packet1.yawspeed , packet1.lat , packet1.lon , packet1.alt , packet1.vx , packet1.vy , packet1.vz , packet1.ind_airspeed , packet1.true_airspeed , packet1.xacc , packet1.yacc , packet1.zacc ); - mavlink_msg_hil_state_quaternion_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_hil_state_quaternion_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.attitude_quaternion , packet1.rollspeed , packet1.pitchspeed , packet1.yawspeed , packet1.lat , packet1.lon , packet1.alt , packet1.vx , packet1.vy , packet1.vz , packet1.ind_airspeed , packet1.true_airspeed , packet1.xacc , packet1.yacc , packet1.zacc ); - mavlink_msg_hil_state_quaternion_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_SCALED_IMU2 >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_scaled_imu2_t packet_in = { - 963497464,17443,17547,17651,17755,17859,17963,18067,18171,18275,18379 - }; - mavlink_scaled_imu2_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_boot_ms = packet_in.time_boot_ms; - packet1.xacc = packet_in.xacc; - packet1.yacc = packet_in.yacc; - packet1.zacc = packet_in.zacc; - packet1.xgyro = packet_in.xgyro; - packet1.ygyro = packet_in.ygyro; - packet1.zgyro = packet_in.zgyro; - packet1.xmag = packet_in.xmag; - packet1.ymag = packet_in.ymag; - packet1.zmag = packet_in.zmag; - packet1.temperature = packet_in.temperature; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_SCALED_IMU2_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SCALED_IMU2_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_scaled_imu2_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_scaled_imu2_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_scaled_imu2_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.xacc , packet1.yacc , packet1.zacc , packet1.xgyro , packet1.ygyro , packet1.zgyro , packet1.xmag , packet1.ymag , packet1.zmag , packet1.temperature ); - mavlink_msg_scaled_imu2_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_scaled_imu2_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.xacc , packet1.yacc , packet1.zacc , packet1.xgyro , packet1.ygyro , packet1.zgyro , packet1.xmag , packet1.ymag , packet1.zmag , packet1.temperature ); - mavlink_msg_scaled_imu2_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_LOG_REQUEST_LIST >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_log_request_list_t packet_in = { - 17235,17339,17,84 - }; - mavlink_log_request_list_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.start = packet_in.start; - packet1.end = packet_in.end; - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_LOG_REQUEST_LIST_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_LOG_REQUEST_LIST_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_log_request_list_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_log_request_list_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_log_request_list_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.start , packet1.end ); - mavlink_msg_log_request_list_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_log_request_list_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.start , packet1.end ); - mavlink_msg_log_request_list_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_LOG_ENTRY >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_log_entry_t packet_in = { - 963497464,963497672,17651,17755,17859 - }; - mavlink_log_entry_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_utc = packet_in.time_utc; - packet1.size = packet_in.size; - packet1.id = packet_in.id; - packet1.num_logs = packet_in.num_logs; - packet1.last_log_num = packet_in.last_log_num; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_LOG_ENTRY_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_LOG_ENTRY_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_log_entry_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_log_entry_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_log_entry_pack(system_id, component_id, &msg , packet1.id , packet1.num_logs , packet1.last_log_num , packet1.time_utc , packet1.size ); - mavlink_msg_log_entry_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_log_entry_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.id , packet1.num_logs , packet1.last_log_num , packet1.time_utc , packet1.size ); - mavlink_msg_log_entry_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_LOG_REQUEST_DATA >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_log_request_data_t packet_in = { - 963497464,963497672,17651,163,230 - }; - mavlink_log_request_data_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.ofs = packet_in.ofs; - packet1.count = packet_in.count; - packet1.id = packet_in.id; - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_LOG_REQUEST_DATA_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_LOG_REQUEST_DATA_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_log_request_data_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_log_request_data_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_log_request_data_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.id , packet1.ofs , packet1.count ); - mavlink_msg_log_request_data_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_log_request_data_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.id , packet1.ofs , packet1.count ); - mavlink_msg_log_request_data_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_LOG_DATA >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_log_data_t packet_in = { - 963497464,17443,151,{ 218, 219, 220, 221, 222, 223, 224, 225, 226, 227, 228, 229, 230, 231, 232, 233, 234, 235, 236, 237, 238, 239, 240, 241, 242, 243, 244, 245, 246, 247, 248, 249, 250, 251, 252, 253, 254, 255, 0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31, 32, 33, 34, 35, 36, 37, 38, 39, 40, 41, 42, 43, 44, 45, 46, 47, 48, 49, 50, 51 } - }; - mavlink_log_data_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.ofs = packet_in.ofs; - packet1.id = packet_in.id; - packet1.count = packet_in.count; - - mav_array_memcpy(packet1.data, packet_in.data, sizeof(uint8_t)*90); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_LOG_DATA_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_LOG_DATA_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_log_data_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_log_data_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_log_data_pack(system_id, component_id, &msg , packet1.id , packet1.ofs , packet1.count , packet1.data ); - mavlink_msg_log_data_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_log_data_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.id , packet1.ofs , packet1.count , packet1.data ); - mavlink_msg_log_data_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_LOG_ERASE >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_log_erase_t packet_in = { - 5,72 - }; - mavlink_log_erase_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_LOG_ERASE_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_LOG_ERASE_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_log_erase_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_log_erase_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_log_erase_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component ); - mavlink_msg_log_erase_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_log_erase_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component ); - mavlink_msg_log_erase_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_LOG_REQUEST_END >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_log_request_end_t packet_in = { - 5,72 - }; - mavlink_log_request_end_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_LOG_REQUEST_END_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_LOG_REQUEST_END_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_log_request_end_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_log_request_end_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_log_request_end_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component ); - mavlink_msg_log_request_end_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_log_request_end_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component ); - mavlink_msg_log_request_end_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_GPS_INJECT_DATA >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_gps_inject_data_t packet_in = { - 5,72,139,{ 206, 207, 208, 209, 210, 211, 212, 213, 214, 215, 216, 217, 218, 219, 220, 221, 222, 223, 224, 225, 226, 227, 228, 229, 230, 231, 232, 233, 234, 235, 236, 237, 238, 239, 240, 241, 242, 243, 244, 245, 246, 247, 248, 249, 250, 251, 252, 253, 254, 255, 0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31, 32, 33, 34, 35, 36, 37, 38, 39, 40, 41, 42, 43, 44, 45, 46, 47, 48, 49, 50, 51, 52, 53, 54, 55, 56, 57, 58, 59 } - }; - mavlink_gps_inject_data_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - packet1.len = packet_in.len; - - mav_array_memcpy(packet1.data, packet_in.data, sizeof(uint8_t)*110); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_GPS_INJECT_DATA_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_GPS_INJECT_DATA_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_gps_inject_data_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_gps_inject_data_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_gps_inject_data_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.len , packet1.data ); - mavlink_msg_gps_inject_data_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_gps_inject_data_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.len , packet1.data ); - mavlink_msg_gps_inject_data_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_GPS2_RAW >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_gps2_raw_t packet_in = { - 93372036854775807ULL,963497880,963498088,963498296,963498504,18483,18587,18691,18795,101,168,235,19055,963499388,963499596,963499804,963500012,963500220 - }; - mavlink_gps2_raw_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_usec = packet_in.time_usec; - packet1.lat = packet_in.lat; - packet1.lon = packet_in.lon; - packet1.alt = packet_in.alt; - packet1.dgps_age = packet_in.dgps_age; - packet1.eph = packet_in.eph; - packet1.epv = packet_in.epv; - packet1.vel = packet_in.vel; - packet1.cog = packet_in.cog; - packet1.fix_type = packet_in.fix_type; - packet1.satellites_visible = packet_in.satellites_visible; - packet1.dgps_numch = packet_in.dgps_numch; - packet1.yaw = packet_in.yaw; - packet1.alt_ellipsoid = packet_in.alt_ellipsoid; - packet1.h_acc = packet_in.h_acc; - packet1.v_acc = packet_in.v_acc; - packet1.vel_acc = packet_in.vel_acc; - packet1.hdg_acc = packet_in.hdg_acc; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_GPS2_RAW_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_GPS2_RAW_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_gps2_raw_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_gps2_raw_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_gps2_raw_pack(system_id, component_id, &msg , packet1.time_usec , packet1.fix_type , packet1.lat , packet1.lon , packet1.alt , packet1.eph , packet1.epv , packet1.vel , packet1.cog , packet1.satellites_visible , packet1.dgps_numch , packet1.dgps_age , packet1.yaw , packet1.alt_ellipsoid , packet1.h_acc , packet1.v_acc , packet1.vel_acc , packet1.hdg_acc ); - mavlink_msg_gps2_raw_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_gps2_raw_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.fix_type , packet1.lat , packet1.lon , packet1.alt , packet1.eph , packet1.epv , packet1.vel , packet1.cog , packet1.satellites_visible , packet1.dgps_numch , packet1.dgps_age , packet1.yaw , packet1.alt_ellipsoid , packet1.h_acc , packet1.v_acc , packet1.vel_acc , packet1.hdg_acc ); - mavlink_msg_gps2_raw_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_POWER_STATUS >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_power_status_t packet_in = { - 17235,17339,17443 - }; - mavlink_power_status_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.Vcc = packet_in.Vcc; - packet1.Vservo = packet_in.Vservo; - packet1.flags = packet_in.flags; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_POWER_STATUS_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_POWER_STATUS_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_power_status_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_power_status_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_power_status_pack(system_id, component_id, &msg , packet1.Vcc , packet1.Vservo , packet1.flags ); - mavlink_msg_power_status_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_power_status_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.Vcc , packet1.Vservo , packet1.flags ); - mavlink_msg_power_status_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_SERIAL_CONTROL >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_serial_control_t packet_in = { - 963497464,17443,151,218,29,{ 96, 97, 98, 99, 100, 101, 102, 103, 104, 105, 106, 107, 108, 109, 110, 111, 112, 113, 114, 115, 116, 117, 118, 119, 120, 121, 122, 123, 124, 125, 126, 127, 128, 129, 130, 131, 132, 133, 134, 135, 136, 137, 138, 139, 140, 141, 142, 143, 144, 145, 146, 147, 148, 149, 150, 151, 152, 153, 154, 155, 156, 157, 158, 159, 160, 161, 162, 163, 164, 165 },178,245 - }; - mavlink_serial_control_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.baudrate = packet_in.baudrate; - packet1.timeout = packet_in.timeout; - packet1.device = packet_in.device; - packet1.flags = packet_in.flags; - packet1.count = packet_in.count; - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - - mav_array_memcpy(packet1.data, packet_in.data, sizeof(uint8_t)*70); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_SERIAL_CONTROL_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SERIAL_CONTROL_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_serial_control_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_serial_control_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_serial_control_pack(system_id, component_id, &msg , packet1.device , packet1.flags , packet1.timeout , packet1.baudrate , packet1.count , packet1.data , packet1.target_system , packet1.target_component ); - mavlink_msg_serial_control_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_serial_control_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.device , packet1.flags , packet1.timeout , packet1.baudrate , packet1.count , packet1.data , packet1.target_system , packet1.target_component ); - mavlink_msg_serial_control_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_GPS_RTK >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_gps_rtk_t packet_in = { - 963497464,963497672,963497880,963498088,963498296,963498504,963498712,18691,223,34,101,168,235 - }; - mavlink_gps_rtk_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_last_baseline_ms = packet_in.time_last_baseline_ms; - packet1.tow = packet_in.tow; - packet1.baseline_a_mm = packet_in.baseline_a_mm; - packet1.baseline_b_mm = packet_in.baseline_b_mm; - packet1.baseline_c_mm = packet_in.baseline_c_mm; - packet1.accuracy = packet_in.accuracy; - packet1.iar_num_hypotheses = packet_in.iar_num_hypotheses; - packet1.wn = packet_in.wn; - packet1.rtk_receiver_id = packet_in.rtk_receiver_id; - packet1.rtk_health = packet_in.rtk_health; - packet1.rtk_rate = packet_in.rtk_rate; - packet1.nsats = packet_in.nsats; - packet1.baseline_coords_type = packet_in.baseline_coords_type; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_GPS_RTK_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_GPS_RTK_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_gps_rtk_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_gps_rtk_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_gps_rtk_pack(system_id, component_id, &msg , packet1.time_last_baseline_ms , packet1.rtk_receiver_id , packet1.wn , packet1.tow , packet1.rtk_health , packet1.rtk_rate , packet1.nsats , packet1.baseline_coords_type , packet1.baseline_a_mm , packet1.baseline_b_mm , packet1.baseline_c_mm , packet1.accuracy , packet1.iar_num_hypotheses ); - mavlink_msg_gps_rtk_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_gps_rtk_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_last_baseline_ms , packet1.rtk_receiver_id , packet1.wn , packet1.tow , packet1.rtk_health , packet1.rtk_rate , packet1.nsats , packet1.baseline_coords_type , packet1.baseline_a_mm , packet1.baseline_b_mm , packet1.baseline_c_mm , packet1.accuracy , packet1.iar_num_hypotheses ); - mavlink_msg_gps_rtk_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_GPS2_RTK >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_gps2_rtk_t packet_in = { - 963497464,963497672,963497880,963498088,963498296,963498504,963498712,18691,223,34,101,168,235 - }; - mavlink_gps2_rtk_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_last_baseline_ms = packet_in.time_last_baseline_ms; - packet1.tow = packet_in.tow; - packet1.baseline_a_mm = packet_in.baseline_a_mm; - packet1.baseline_b_mm = packet_in.baseline_b_mm; - packet1.baseline_c_mm = packet_in.baseline_c_mm; - packet1.accuracy = packet_in.accuracy; - packet1.iar_num_hypotheses = packet_in.iar_num_hypotheses; - packet1.wn = packet_in.wn; - packet1.rtk_receiver_id = packet_in.rtk_receiver_id; - packet1.rtk_health = packet_in.rtk_health; - packet1.rtk_rate = packet_in.rtk_rate; - packet1.nsats = packet_in.nsats; - packet1.baseline_coords_type = packet_in.baseline_coords_type; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_GPS2_RTK_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_GPS2_RTK_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_gps2_rtk_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_gps2_rtk_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_gps2_rtk_pack(system_id, component_id, &msg , packet1.time_last_baseline_ms , packet1.rtk_receiver_id , packet1.wn , packet1.tow , packet1.rtk_health , packet1.rtk_rate , packet1.nsats , packet1.baseline_coords_type , packet1.baseline_a_mm , packet1.baseline_b_mm , packet1.baseline_c_mm , packet1.accuracy , packet1.iar_num_hypotheses ); - mavlink_msg_gps2_rtk_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_gps2_rtk_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_last_baseline_ms , packet1.rtk_receiver_id , packet1.wn , packet1.tow , packet1.rtk_health , packet1.rtk_rate , packet1.nsats , packet1.baseline_coords_type , packet1.baseline_a_mm , packet1.baseline_b_mm , packet1.baseline_c_mm , packet1.accuracy , packet1.iar_num_hypotheses ); - mavlink_msg_gps2_rtk_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_SCALED_IMU3 >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_scaled_imu3_t packet_in = { - 963497464,17443,17547,17651,17755,17859,17963,18067,18171,18275,18379 - }; - mavlink_scaled_imu3_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_boot_ms = packet_in.time_boot_ms; - packet1.xacc = packet_in.xacc; - packet1.yacc = packet_in.yacc; - packet1.zacc = packet_in.zacc; - packet1.xgyro = packet_in.xgyro; - packet1.ygyro = packet_in.ygyro; - packet1.zgyro = packet_in.zgyro; - packet1.xmag = packet_in.xmag; - packet1.ymag = packet_in.ymag; - packet1.zmag = packet_in.zmag; - packet1.temperature = packet_in.temperature; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_SCALED_IMU3_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SCALED_IMU3_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_scaled_imu3_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_scaled_imu3_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_scaled_imu3_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.xacc , packet1.yacc , packet1.zacc , packet1.xgyro , packet1.ygyro , packet1.zgyro , packet1.xmag , packet1.ymag , packet1.zmag , packet1.temperature ); - mavlink_msg_scaled_imu3_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_scaled_imu3_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.xacc , packet1.yacc , packet1.zacc , packet1.xgyro , packet1.ygyro , packet1.zgyro , packet1.xmag , packet1.ymag , packet1.zmag , packet1.temperature ); - mavlink_msg_scaled_imu3_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_data_transmission_handshake_t packet_in = { - 963497464,17443,17547,17651,163,230,41 - }; - mavlink_data_transmission_handshake_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.size = packet_in.size; - packet1.width = packet_in.width; - packet1.height = packet_in.height; - packet1.packets = packet_in.packets; - packet1.type = packet_in.type; - packet1.payload = packet_in.payload; - packet1.jpg_quality = packet_in.jpg_quality; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_data_transmission_handshake_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_data_transmission_handshake_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_data_transmission_handshake_pack(system_id, component_id, &msg , packet1.type , packet1.size , packet1.width , packet1.height , packet1.packets , packet1.payload , packet1.jpg_quality ); - mavlink_msg_data_transmission_handshake_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_data_transmission_handshake_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.type , packet1.size , packet1.width , packet1.height , packet1.packets , packet1.payload , packet1.jpg_quality ); - mavlink_msg_data_transmission_handshake_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_ENCAPSULATED_DATA >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_encapsulated_data_t packet_in = { - 17235,{ 139, 140, 141, 142, 143, 144, 145, 146, 147, 148, 149, 150, 151, 152, 153, 154, 155, 156, 157, 158, 159, 160, 161, 162, 163, 164, 165, 166, 167, 168, 169, 170, 171, 172, 173, 174, 175, 176, 177, 178, 179, 180, 181, 182, 183, 184, 185, 186, 187, 188, 189, 190, 191, 192, 193, 194, 195, 196, 197, 198, 199, 200, 201, 202, 203, 204, 205, 206, 207, 208, 209, 210, 211, 212, 213, 214, 215, 216, 217, 218, 219, 220, 221, 222, 223, 224, 225, 226, 227, 228, 229, 230, 231, 232, 233, 234, 235, 236, 237, 238, 239, 240, 241, 242, 243, 244, 245, 246, 247, 248, 249, 250, 251, 252, 253, 254, 255, 0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31, 32, 33, 34, 35, 36, 37, 38, 39, 40, 41, 42, 43, 44, 45, 46, 47, 48, 49, 50, 51, 52, 53, 54, 55, 56, 57, 58, 59, 60, 61, 62, 63, 64, 65, 66, 67, 68, 69, 70, 71, 72, 73, 74, 75, 76, 77, 78, 79, 80, 81, 82, 83, 84, 85, 86, 87, 88, 89, 90, 91, 92, 93, 94, 95, 96, 97, 98, 99, 100, 101, 102, 103, 104, 105, 106, 107, 108, 109, 110, 111, 112, 113, 114, 115, 116, 117, 118, 119, 120, 121, 122, 123, 124, 125, 126, 127, 128, 129, 130, 131, 132, 133, 134, 135 } - }; - mavlink_encapsulated_data_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.seqnr = packet_in.seqnr; - - mav_array_memcpy(packet1.data, packet_in.data, sizeof(uint8_t)*253); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_ENCAPSULATED_DATA_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_ENCAPSULATED_DATA_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_encapsulated_data_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_encapsulated_data_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_encapsulated_data_pack(system_id, component_id, &msg , packet1.seqnr , packet1.data ); - mavlink_msg_encapsulated_data_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_encapsulated_data_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.seqnr , packet1.data ); - mavlink_msg_encapsulated_data_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_DISTANCE_SENSOR >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_distance_sensor_t packet_in = { - 963497464,17443,17547,17651,163,230,41,108,115.0,143.0,{ 171.0, 172.0, 173.0, 174.0 },247 - }; - mavlink_distance_sensor_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_boot_ms = packet_in.time_boot_ms; - packet1.min_distance = packet_in.min_distance; - packet1.max_distance = packet_in.max_distance; - packet1.current_distance = packet_in.current_distance; - packet1.type = packet_in.type; - packet1.id = packet_in.id; - packet1.orientation = packet_in.orientation; - packet1.covariance = packet_in.covariance; - packet1.horizontal_fov = packet_in.horizontal_fov; - packet1.vertical_fov = packet_in.vertical_fov; - packet1.signal_quality = packet_in.signal_quality; - - mav_array_memcpy(packet1.quaternion, packet_in.quaternion, sizeof(float)*4); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_DISTANCE_SENSOR_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_DISTANCE_SENSOR_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_distance_sensor_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_distance_sensor_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_distance_sensor_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.min_distance , packet1.max_distance , packet1.current_distance , packet1.type , packet1.id , packet1.orientation , packet1.covariance , packet1.horizontal_fov , packet1.vertical_fov , packet1.quaternion , packet1.signal_quality ); - mavlink_msg_distance_sensor_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_distance_sensor_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.min_distance , packet1.max_distance , packet1.current_distance , packet1.type , packet1.id , packet1.orientation , packet1.covariance , packet1.horizontal_fov , packet1.vertical_fov , packet1.quaternion , packet1.signal_quality ); - mavlink_msg_distance_sensor_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_TERRAIN_REQUEST >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_terrain_request_t packet_in = { - 93372036854775807ULL,963497880,963498088,18067 - }; - mavlink_terrain_request_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.mask = packet_in.mask; - packet1.lat = packet_in.lat; - packet1.lon = packet_in.lon; - packet1.grid_spacing = packet_in.grid_spacing; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_TERRAIN_REQUEST_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_TERRAIN_REQUEST_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_terrain_request_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_terrain_request_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_terrain_request_pack(system_id, component_id, &msg , packet1.lat , packet1.lon , packet1.grid_spacing , packet1.mask ); - mavlink_msg_terrain_request_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_terrain_request_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.lat , packet1.lon , packet1.grid_spacing , packet1.mask ); - mavlink_msg_terrain_request_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_TERRAIN_DATA >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_terrain_data_t packet_in = { - 963497464,963497672,17651,{ 17755, 17756, 17757, 17758, 17759, 17760, 17761, 17762, 17763, 17764, 17765, 17766, 17767, 17768, 17769, 17770 },3 - }; - mavlink_terrain_data_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.lat = packet_in.lat; - packet1.lon = packet_in.lon; - packet1.grid_spacing = packet_in.grid_spacing; - packet1.gridbit = packet_in.gridbit; - - mav_array_memcpy(packet1.data, packet_in.data, sizeof(int16_t)*16); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_TERRAIN_DATA_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_TERRAIN_DATA_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_terrain_data_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_terrain_data_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_terrain_data_pack(system_id, component_id, &msg , packet1.lat , packet1.lon , packet1.grid_spacing , packet1.gridbit , packet1.data ); - mavlink_msg_terrain_data_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_terrain_data_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.lat , packet1.lon , packet1.grid_spacing , packet1.gridbit , packet1.data ); - mavlink_msg_terrain_data_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_TERRAIN_CHECK >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_terrain_check_t packet_in = { - 963497464,963497672 - }; - mavlink_terrain_check_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.lat = packet_in.lat; - packet1.lon = packet_in.lon; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_TERRAIN_CHECK_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_TERRAIN_CHECK_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_terrain_check_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_terrain_check_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_terrain_check_pack(system_id, component_id, &msg , packet1.lat , packet1.lon ); - mavlink_msg_terrain_check_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_terrain_check_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.lat , packet1.lon ); - mavlink_msg_terrain_check_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_TERRAIN_REPORT >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_terrain_report_t packet_in = { - 963497464,963497672,73.0,101.0,18067,18171,18275 - }; - mavlink_terrain_report_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.lat = packet_in.lat; - packet1.lon = packet_in.lon; - packet1.terrain_height = packet_in.terrain_height; - packet1.current_height = packet_in.current_height; - packet1.spacing = packet_in.spacing; - packet1.pending = packet_in.pending; - packet1.loaded = packet_in.loaded; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_TERRAIN_REPORT_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_TERRAIN_REPORT_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_terrain_report_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_terrain_report_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_terrain_report_pack(system_id, component_id, &msg , packet1.lat , packet1.lon , packet1.spacing , packet1.terrain_height , packet1.current_height , packet1.pending , packet1.loaded ); - mavlink_msg_terrain_report_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_terrain_report_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.lat , packet1.lon , packet1.spacing , packet1.terrain_height , packet1.current_height , packet1.pending , packet1.loaded ); - mavlink_msg_terrain_report_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_SCALED_PRESSURE2 >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_scaled_pressure2_t packet_in = { - 963497464,45.0,73.0,17859,17963 - }; - mavlink_scaled_pressure2_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_boot_ms = packet_in.time_boot_ms; - packet1.press_abs = packet_in.press_abs; - packet1.press_diff = packet_in.press_diff; - packet1.temperature = packet_in.temperature; - packet1.temperature_press_diff = packet_in.temperature_press_diff; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_SCALED_PRESSURE2_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SCALED_PRESSURE2_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_scaled_pressure2_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_scaled_pressure2_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_scaled_pressure2_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.press_abs , packet1.press_diff , packet1.temperature , packet1.temperature_press_diff ); - mavlink_msg_scaled_pressure2_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_scaled_pressure2_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.press_abs , packet1.press_diff , packet1.temperature , packet1.temperature_press_diff ); - mavlink_msg_scaled_pressure2_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_ATT_POS_MOCAP >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_att_pos_mocap_t packet_in = { - 93372036854775807ULL,{ 73.0, 74.0, 75.0, 76.0 },185.0,213.0,241.0,{ 269.0, 270.0, 271.0, 272.0, 273.0, 274.0, 275.0, 276.0, 277.0, 278.0, 279.0, 280.0, 281.0, 282.0, 283.0, 284.0, 285.0, 286.0, 287.0, 288.0, 289.0 } - }; - mavlink_att_pos_mocap_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_usec = packet_in.time_usec; - packet1.x = packet_in.x; - packet1.y = packet_in.y; - packet1.z = packet_in.z; - - mav_array_memcpy(packet1.q, packet_in.q, sizeof(float)*4); - mav_array_memcpy(packet1.covariance, packet_in.covariance, sizeof(float)*21); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_ATT_POS_MOCAP_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_ATT_POS_MOCAP_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_att_pos_mocap_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_att_pos_mocap_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_att_pos_mocap_pack(system_id, component_id, &msg , packet1.time_usec , packet1.q , packet1.x , packet1.y , packet1.z , packet1.covariance ); - mavlink_msg_att_pos_mocap_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_att_pos_mocap_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.q , packet1.x , packet1.y , packet1.z , packet1.covariance ); - mavlink_msg_att_pos_mocap_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_set_actuator_control_target_t packet_in = { - 93372036854775807ULL,{ 73.0, 74.0, 75.0, 76.0, 77.0, 78.0, 79.0, 80.0 },125,192,3 - }; - mavlink_set_actuator_control_target_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_usec = packet_in.time_usec; - packet1.group_mlx = packet_in.group_mlx; - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - - mav_array_memcpy(packet1.controls, packet_in.controls, sizeof(float)*8); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_set_actuator_control_target_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_set_actuator_control_target_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_set_actuator_control_target_pack(system_id, component_id, &msg , packet1.time_usec , packet1.group_mlx , packet1.target_system , packet1.target_component , packet1.controls ); - mavlink_msg_set_actuator_control_target_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_set_actuator_control_target_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.group_mlx , packet1.target_system , packet1.target_component , packet1.controls ); - mavlink_msg_set_actuator_control_target_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_actuator_control_target_t packet_in = { - 93372036854775807ULL,{ 73.0, 74.0, 75.0, 76.0, 77.0, 78.0, 79.0, 80.0 },125 - }; - mavlink_actuator_control_target_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_usec = packet_in.time_usec; - packet1.group_mlx = packet_in.group_mlx; - - mav_array_memcpy(packet1.controls, packet_in.controls, sizeof(float)*8); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_actuator_control_target_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_actuator_control_target_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_actuator_control_target_pack(system_id, component_id, &msg , packet1.time_usec , packet1.group_mlx , packet1.controls ); - mavlink_msg_actuator_control_target_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_actuator_control_target_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.group_mlx , packet1.controls ); - mavlink_msg_actuator_control_target_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_ALTITUDE >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_altitude_t packet_in = { - 93372036854775807ULL,73.0,101.0,129.0,157.0,185.0,213.0 - }; - mavlink_altitude_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_usec = packet_in.time_usec; - packet1.altitude_monotonic = packet_in.altitude_monotonic; - packet1.altitude_amsl = packet_in.altitude_amsl; - packet1.altitude_local = packet_in.altitude_local; - packet1.altitude_relative = packet_in.altitude_relative; - packet1.altitude_terrain = packet_in.altitude_terrain; - packet1.bottom_clearance = packet_in.bottom_clearance; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_ALTITUDE_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_ALTITUDE_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_altitude_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_altitude_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_altitude_pack(system_id, component_id, &msg , packet1.time_usec , packet1.altitude_monotonic , packet1.altitude_amsl , packet1.altitude_local , packet1.altitude_relative , packet1.altitude_terrain , packet1.bottom_clearance ); - mavlink_msg_altitude_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_altitude_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.altitude_monotonic , packet1.altitude_amsl , packet1.altitude_local , packet1.altitude_relative , packet1.altitude_terrain , packet1.bottom_clearance ); - mavlink_msg_altitude_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_RESOURCE_REQUEST >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_resource_request_t packet_in = { - 5,72,{ 139, 140, 141, 142, 143, 144, 145, 146, 147, 148, 149, 150, 151, 152, 153, 154, 155, 156, 157, 158, 159, 160, 161, 162, 163, 164, 165, 166, 167, 168, 169, 170, 171, 172, 173, 174, 175, 176, 177, 178, 179, 180, 181, 182, 183, 184, 185, 186, 187, 188, 189, 190, 191, 192, 193, 194, 195, 196, 197, 198, 199, 200, 201, 202, 203, 204, 205, 206, 207, 208, 209, 210, 211, 212, 213, 214, 215, 216, 217, 218, 219, 220, 221, 222, 223, 224, 225, 226, 227, 228, 229, 230, 231, 232, 233, 234, 235, 236, 237, 238, 239, 240, 241, 242, 243, 244, 245, 246, 247, 248, 249, 250, 251, 252, 253, 254, 255, 0, 1, 2 },243,{ 54, 55, 56, 57, 58, 59, 60, 61, 62, 63, 64, 65, 66, 67, 68, 69, 70, 71, 72, 73, 74, 75, 76, 77, 78, 79, 80, 81, 82, 83, 84, 85, 86, 87, 88, 89, 90, 91, 92, 93, 94, 95, 96, 97, 98, 99, 100, 101, 102, 103, 104, 105, 106, 107, 108, 109, 110, 111, 112, 113, 114, 115, 116, 117, 118, 119, 120, 121, 122, 123, 124, 125, 126, 127, 128, 129, 130, 131, 132, 133, 134, 135, 136, 137, 138, 139, 140, 141, 142, 143, 144, 145, 146, 147, 148, 149, 150, 151, 152, 153, 154, 155, 156, 157, 158, 159, 160, 161, 162, 163, 164, 165, 166, 167, 168, 169, 170, 171, 172, 173 } - }; - mavlink_resource_request_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.request_id = packet_in.request_id; - packet1.uri_type = packet_in.uri_type; - packet1.transfer_type = packet_in.transfer_type; - - mav_array_memcpy(packet1.uri, packet_in.uri, sizeof(uint8_t)*120); - mav_array_memcpy(packet1.storage, packet_in.storage, sizeof(uint8_t)*120); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_RESOURCE_REQUEST_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_RESOURCE_REQUEST_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_resource_request_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_resource_request_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_resource_request_pack(system_id, component_id, &msg , packet1.request_id , packet1.uri_type , packet1.uri , packet1.transfer_type , packet1.storage ); - mavlink_msg_resource_request_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_resource_request_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.request_id , packet1.uri_type , packet1.uri , packet1.transfer_type , packet1.storage ); - mavlink_msg_resource_request_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_SCALED_PRESSURE3 >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_scaled_pressure3_t packet_in = { - 963497464,45.0,73.0,17859,17963 - }; - mavlink_scaled_pressure3_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_boot_ms = packet_in.time_boot_ms; - packet1.press_abs = packet_in.press_abs; - packet1.press_diff = packet_in.press_diff; - packet1.temperature = packet_in.temperature; - packet1.temperature_press_diff = packet_in.temperature_press_diff; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_SCALED_PRESSURE3_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SCALED_PRESSURE3_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_scaled_pressure3_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_scaled_pressure3_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_scaled_pressure3_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.press_abs , packet1.press_diff , packet1.temperature , packet1.temperature_press_diff ); - mavlink_msg_scaled_pressure3_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_scaled_pressure3_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.press_abs , packet1.press_diff , packet1.temperature , packet1.temperature_press_diff ); - mavlink_msg_scaled_pressure3_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_FOLLOW_TARGET >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_follow_target_t packet_in = { - 93372036854775807ULL,93372036854776311ULL,963498296,963498504,185.0,{ 213.0, 214.0, 215.0 },{ 297.0, 298.0, 299.0 },{ 381.0, 382.0, 383.0, 384.0 },{ 493.0, 494.0, 495.0 },{ 577.0, 578.0, 579.0 },25 - }; - mavlink_follow_target_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.timestamp = packet_in.timestamp; - packet1.custom_state = packet_in.custom_state; - packet1.lat = packet_in.lat; - packet1.lon = packet_in.lon; - packet1.alt = packet_in.alt; - packet1.est_capabilities = packet_in.est_capabilities; - - mav_array_memcpy(packet1.vel, packet_in.vel, sizeof(float)*3); - mav_array_memcpy(packet1.acc, packet_in.acc, sizeof(float)*3); - mav_array_memcpy(packet1.attitude_q, packet_in.attitude_q, sizeof(float)*4); - mav_array_memcpy(packet1.rates, packet_in.rates, sizeof(float)*3); - mav_array_memcpy(packet1.position_cov, packet_in.position_cov, sizeof(float)*3); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_FOLLOW_TARGET_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_FOLLOW_TARGET_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_follow_target_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_follow_target_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_follow_target_pack(system_id, component_id, &msg , packet1.timestamp , packet1.est_capabilities , packet1.lat , packet1.lon , packet1.alt , packet1.vel , packet1.acc , packet1.attitude_q , packet1.rates , packet1.position_cov , packet1.custom_state ); - mavlink_msg_follow_target_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_follow_target_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.est_capabilities , packet1.lat , packet1.lon , packet1.alt , packet1.vel , packet1.acc , packet1.attitude_q , packet1.rates , packet1.position_cov , packet1.custom_state ); - mavlink_msg_follow_target_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_control_system_state_t packet_in = { - 93372036854775807ULL,73.0,101.0,129.0,157.0,185.0,213.0,241.0,269.0,297.0,325.0,{ 353.0, 354.0, 355.0 },{ 437.0, 438.0, 439.0 },{ 521.0, 522.0, 523.0, 524.0 },633.0,661.0,689.0 - }; - mavlink_control_system_state_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_usec = packet_in.time_usec; - packet1.x_acc = packet_in.x_acc; - packet1.y_acc = packet_in.y_acc; - packet1.z_acc = packet_in.z_acc; - packet1.x_vel = packet_in.x_vel; - packet1.y_vel = packet_in.y_vel; - packet1.z_vel = packet_in.z_vel; - packet1.x_pos = packet_in.x_pos; - packet1.y_pos = packet_in.y_pos; - packet1.z_pos = packet_in.z_pos; - packet1.airspeed = packet_in.airspeed; - packet1.roll_rate = packet_in.roll_rate; - packet1.pitch_rate = packet_in.pitch_rate; - packet1.yaw_rate = packet_in.yaw_rate; - - mav_array_memcpy(packet1.vel_variance, packet_in.vel_variance, sizeof(float)*3); - mav_array_memcpy(packet1.pos_variance, packet_in.pos_variance, sizeof(float)*3); - mav_array_memcpy(packet1.q, packet_in.q, sizeof(float)*4); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_CONTROL_SYSTEM_STATE_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_control_system_state_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_control_system_state_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_control_system_state_pack(system_id, component_id, &msg , packet1.time_usec , packet1.x_acc , packet1.y_acc , packet1.z_acc , packet1.x_vel , packet1.y_vel , packet1.z_vel , packet1.x_pos , packet1.y_pos , packet1.z_pos , packet1.airspeed , packet1.vel_variance , packet1.pos_variance , packet1.q , packet1.roll_rate , packet1.pitch_rate , packet1.yaw_rate ); - mavlink_msg_control_system_state_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_control_system_state_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.x_acc , packet1.y_acc , packet1.z_acc , packet1.x_vel , packet1.y_vel , packet1.z_vel , packet1.x_pos , packet1.y_pos , packet1.z_pos , packet1.airspeed , packet1.vel_variance , packet1.pos_variance , packet1.q , packet1.roll_rate , packet1.pitch_rate , packet1.yaw_rate ); - mavlink_msg_control_system_state_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_BATTERY_STATUS >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_battery_status_t packet_in = { - 963497464,963497672,17651,{ 17755, 17756, 17757, 17758, 17759, 17760, 17761, 17762, 17763, 17764 },18795,101,168,235,46,963499336,125,{ 19367, 19368, 19369, 19370 },216,963500064 - }; - mavlink_battery_status_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.current_consumed = packet_in.current_consumed; - packet1.energy_consumed = packet_in.energy_consumed; - packet1.temperature = packet_in.temperature; - packet1.current_battery = packet_in.current_battery; - packet1.id = packet_in.id; - packet1.battery_function = packet_in.battery_function; - packet1.type = packet_in.type; - packet1.battery_remaining = packet_in.battery_remaining; - packet1.time_remaining = packet_in.time_remaining; - packet1.charge_state = packet_in.charge_state; - packet1.mode = packet_in.mode; - packet1.fault_bitmask = packet_in.fault_bitmask; - - mav_array_memcpy(packet1.voltages, packet_in.voltages, sizeof(uint16_t)*10); - mav_array_memcpy(packet1.voltages_ext, packet_in.voltages_ext, sizeof(uint16_t)*4); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_BATTERY_STATUS_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_BATTERY_STATUS_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_battery_status_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_battery_status_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_battery_status_pack(system_id, component_id, &msg , packet1.id , packet1.battery_function , packet1.type , packet1.temperature , packet1.voltages , packet1.current_battery , packet1.current_consumed , packet1.energy_consumed , packet1.battery_remaining , packet1.time_remaining , packet1.charge_state , packet1.voltages_ext , packet1.mode , packet1.fault_bitmask ); - mavlink_msg_battery_status_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_battery_status_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.id , packet1.battery_function , packet1.type , packet1.temperature , packet1.voltages , packet1.current_battery , packet1.current_consumed , packet1.energy_consumed , packet1.battery_remaining , packet1.time_remaining , packet1.charge_state , packet1.voltages_ext , packet1.mode , packet1.fault_bitmask ); - mavlink_msg_battery_status_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_AUTOPILOT_VERSION >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_autopilot_version_t packet_in = { - 93372036854775807ULL,93372036854776311ULL,963498296,963498504,963498712,963498920,18899,19003,{ 113, 114, 115, 116, 117, 118, 119, 120 },{ 137, 138, 139, 140, 141, 142, 143, 144 },{ 161, 162, 163, 164, 165, 166, 167, 168 },{ 185, 186, 187, 188, 189, 190, 191, 192, 193, 194, 195, 196, 197, 198, 199, 200, 201, 202 } - }; - mavlink_autopilot_version_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.capabilities = packet_in.capabilities; - packet1.uid = packet_in.uid; - packet1.flight_sw_version = packet_in.flight_sw_version; - packet1.middleware_sw_version = packet_in.middleware_sw_version; - packet1.os_sw_version = packet_in.os_sw_version; - packet1.board_version = packet_in.board_version; - packet1.vendor_id = packet_in.vendor_id; - packet1.product_id = packet_in.product_id; - - mav_array_memcpy(packet1.flight_custom_version, packet_in.flight_custom_version, sizeof(uint8_t)*8); - mav_array_memcpy(packet1.middleware_custom_version, packet_in.middleware_custom_version, sizeof(uint8_t)*8); - mav_array_memcpy(packet1.os_custom_version, packet_in.os_custom_version, sizeof(uint8_t)*8); - mav_array_memcpy(packet1.uid2, packet_in.uid2, sizeof(uint8_t)*18); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_AUTOPILOT_VERSION_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_AUTOPILOT_VERSION_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_autopilot_version_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_autopilot_version_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_autopilot_version_pack(system_id, component_id, &msg , packet1.capabilities , packet1.flight_sw_version , packet1.middleware_sw_version , packet1.os_sw_version , packet1.board_version , packet1.flight_custom_version , packet1.middleware_custom_version , packet1.os_custom_version , packet1.vendor_id , packet1.product_id , packet1.uid , packet1.uid2 ); - mavlink_msg_autopilot_version_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_autopilot_version_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.capabilities , packet1.flight_sw_version , packet1.middleware_sw_version , packet1.os_sw_version , packet1.board_version , packet1.flight_custom_version , packet1.middleware_custom_version , packet1.os_custom_version , packet1.vendor_id , packet1.product_id , packet1.uid , packet1.uid2 ); - mavlink_msg_autopilot_version_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_LANDING_TARGET >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_landing_target_t packet_in = { - 93372036854775807ULL,73.0,101.0,129.0,157.0,185.0,89,156,227.0,255.0,283.0,{ 311.0, 312.0, 313.0, 314.0 },51,118 - }; - mavlink_landing_target_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_usec = packet_in.time_usec; - packet1.angle_x = packet_in.angle_x; - packet1.angle_y = packet_in.angle_y; - packet1.distance = packet_in.distance; - packet1.size_x = packet_in.size_x; - packet1.size_y = packet_in.size_y; - packet1.target_num = packet_in.target_num; - packet1.frame = packet_in.frame; - packet1.x = packet_in.x; - packet1.y = packet_in.y; - packet1.z = packet_in.z; - packet1.type = packet_in.type; - packet1.position_valid = packet_in.position_valid; - - mav_array_memcpy(packet1.q, packet_in.q, sizeof(float)*4); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_LANDING_TARGET_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_LANDING_TARGET_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_landing_target_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_landing_target_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_landing_target_pack(system_id, component_id, &msg , packet1.time_usec , packet1.target_num , packet1.frame , packet1.angle_x , packet1.angle_y , packet1.distance , packet1.size_x , packet1.size_y , packet1.x , packet1.y , packet1.z , packet1.q , packet1.type , packet1.position_valid ); - mavlink_msg_landing_target_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_landing_target_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.target_num , packet1.frame , packet1.angle_x , packet1.angle_y , packet1.distance , packet1.size_x , packet1.size_y , packet1.x , packet1.y , packet1.z , packet1.q , packet1.type , packet1.position_valid ); - mavlink_msg_landing_target_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_FENCE_STATUS >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_fence_status_t packet_in = { - 963497464,17443,151,218,29 - }; - mavlink_fence_status_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.breach_time = packet_in.breach_time; - packet1.breach_count = packet_in.breach_count; - packet1.breach_status = packet_in.breach_status; - packet1.breach_type = packet_in.breach_type; - packet1.breach_mitigation = packet_in.breach_mitigation; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_FENCE_STATUS_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_FENCE_STATUS_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_fence_status_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_fence_status_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_fence_status_pack(system_id, component_id, &msg , packet1.breach_status , packet1.breach_count , packet1.breach_type , packet1.breach_time , packet1.breach_mitigation ); - mavlink_msg_fence_status_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_fence_status_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.breach_status , packet1.breach_count , packet1.breach_type , packet1.breach_time , packet1.breach_mitigation ); - mavlink_msg_fence_status_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_MAG_CAL_REPORT >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_mag_cal_report_t packet_in = { - 17.0,45.0,73.0,101.0,129.0,157.0,185.0,213.0,241.0,269.0,125,192,3,70,325.0,149,216,367.0 - }; - mavlink_mag_cal_report_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.fitness = packet_in.fitness; - packet1.ofs_x = packet_in.ofs_x; - packet1.ofs_y = packet_in.ofs_y; - packet1.ofs_z = packet_in.ofs_z; - packet1.diag_x = packet_in.diag_x; - packet1.diag_y = packet_in.diag_y; - packet1.diag_z = packet_in.diag_z; - packet1.offdiag_x = packet_in.offdiag_x; - packet1.offdiag_y = packet_in.offdiag_y; - packet1.offdiag_z = packet_in.offdiag_z; - packet1.compass_id = packet_in.compass_id; - packet1.cal_mask = packet_in.cal_mask; - packet1.cal_status = packet_in.cal_status; - packet1.autosaved = packet_in.autosaved; - packet1.orientation_confidence = packet_in.orientation_confidence; - packet1.old_orientation = packet_in.old_orientation; - packet1.new_orientation = packet_in.new_orientation; - packet1.scale_factor = packet_in.scale_factor; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_MAG_CAL_REPORT_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_MAG_CAL_REPORT_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_mag_cal_report_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_mag_cal_report_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_mag_cal_report_pack(system_id, component_id, &msg , packet1.compass_id , packet1.cal_mask , packet1.cal_status , packet1.autosaved , packet1.fitness , packet1.ofs_x , packet1.ofs_y , packet1.ofs_z , packet1.diag_x , packet1.diag_y , packet1.diag_z , packet1.offdiag_x , packet1.offdiag_y , packet1.offdiag_z , packet1.orientation_confidence , packet1.old_orientation , packet1.new_orientation , packet1.scale_factor ); - mavlink_msg_mag_cal_report_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_mag_cal_report_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.compass_id , packet1.cal_mask , packet1.cal_status , packet1.autosaved , packet1.fitness , packet1.ofs_x , packet1.ofs_y , packet1.ofs_z , packet1.diag_x , packet1.diag_y , packet1.diag_z , packet1.offdiag_x , packet1.offdiag_y , packet1.offdiag_z , packet1.orientation_confidence , packet1.old_orientation , packet1.new_orientation , packet1.scale_factor ); - mavlink_msg_mag_cal_report_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_EFI_STATUS >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_efi_status_t packet_in = { - 17.0,45.0,73.0,101.0,129.0,157.0,185.0,213.0,241.0,269.0,297.0,325.0,353.0,381.0,409.0,437.0,197,472.0,500.0 - }; - mavlink_efi_status_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.ecu_index = packet_in.ecu_index; - packet1.rpm = packet_in.rpm; - packet1.fuel_consumed = packet_in.fuel_consumed; - packet1.fuel_flow = packet_in.fuel_flow; - packet1.engine_load = packet_in.engine_load; - packet1.throttle_position = packet_in.throttle_position; - packet1.spark_dwell_time = packet_in.spark_dwell_time; - packet1.barometric_pressure = packet_in.barometric_pressure; - packet1.intake_manifold_pressure = packet_in.intake_manifold_pressure; - packet1.intake_manifold_temperature = packet_in.intake_manifold_temperature; - packet1.cylinder_head_temperature = packet_in.cylinder_head_temperature; - packet1.ignition_timing = packet_in.ignition_timing; - packet1.injection_time = packet_in.injection_time; - packet1.exhaust_gas_temperature = packet_in.exhaust_gas_temperature; - packet1.throttle_out = packet_in.throttle_out; - packet1.pt_compensation = packet_in.pt_compensation; - packet1.health = packet_in.health; - packet1.ignition_voltage = packet_in.ignition_voltage; - packet1.fuel_pressure = packet_in.fuel_pressure; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_EFI_STATUS_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_EFI_STATUS_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_efi_status_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_efi_status_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_efi_status_pack(system_id, component_id, &msg , packet1.health , packet1.ecu_index , packet1.rpm , packet1.fuel_consumed , packet1.fuel_flow , packet1.engine_load , packet1.throttle_position , packet1.spark_dwell_time , packet1.barometric_pressure , packet1.intake_manifold_pressure , packet1.intake_manifold_temperature , packet1.cylinder_head_temperature , packet1.ignition_timing , packet1.injection_time , packet1.exhaust_gas_temperature , packet1.throttle_out , packet1.pt_compensation , packet1.ignition_voltage , packet1.fuel_pressure ); - mavlink_msg_efi_status_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_efi_status_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.health , packet1.ecu_index , packet1.rpm , packet1.fuel_consumed , packet1.fuel_flow , packet1.engine_load , packet1.throttle_position , packet1.spark_dwell_time , packet1.barometric_pressure , packet1.intake_manifold_pressure , packet1.intake_manifold_temperature , packet1.cylinder_head_temperature , packet1.ignition_timing , packet1.injection_time , packet1.exhaust_gas_temperature , packet1.throttle_out , packet1.pt_compensation , packet1.ignition_voltage , packet1.fuel_pressure ); - mavlink_msg_efi_status_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_ESTIMATOR_STATUS >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_estimator_status_t packet_in = { - 93372036854775807ULL,73.0,101.0,129.0,157.0,185.0,213.0,241.0,269.0,19315 - }; - mavlink_estimator_status_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_usec = packet_in.time_usec; - packet1.vel_ratio = packet_in.vel_ratio; - packet1.pos_horiz_ratio = packet_in.pos_horiz_ratio; - packet1.pos_vert_ratio = packet_in.pos_vert_ratio; - packet1.mag_ratio = packet_in.mag_ratio; - packet1.hagl_ratio = packet_in.hagl_ratio; - packet1.tas_ratio = packet_in.tas_ratio; - packet1.pos_horiz_accuracy = packet_in.pos_horiz_accuracy; - packet1.pos_vert_accuracy = packet_in.pos_vert_accuracy; - packet1.flags = packet_in.flags; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_ESTIMATOR_STATUS_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_ESTIMATOR_STATUS_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_estimator_status_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_estimator_status_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_estimator_status_pack(system_id, component_id, &msg , packet1.time_usec , packet1.flags , packet1.vel_ratio , packet1.pos_horiz_ratio , packet1.pos_vert_ratio , packet1.mag_ratio , packet1.hagl_ratio , packet1.tas_ratio , packet1.pos_horiz_accuracy , packet1.pos_vert_accuracy ); - mavlink_msg_estimator_status_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_estimator_status_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.flags , packet1.vel_ratio , packet1.pos_horiz_ratio , packet1.pos_vert_ratio , packet1.mag_ratio , packet1.hagl_ratio , packet1.tas_ratio , packet1.pos_horiz_accuracy , packet1.pos_vert_accuracy ); - mavlink_msg_estimator_status_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_WIND_COV >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_wind_cov_t packet_in = { - 93372036854775807ULL,73.0,101.0,129.0,157.0,185.0,213.0,241.0,269.0 - }; - mavlink_wind_cov_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_usec = packet_in.time_usec; - packet1.wind_x = packet_in.wind_x; - packet1.wind_y = packet_in.wind_y; - packet1.wind_z = packet_in.wind_z; - packet1.var_horiz = packet_in.var_horiz; - packet1.var_vert = packet_in.var_vert; - packet1.wind_alt = packet_in.wind_alt; - packet1.horiz_accuracy = packet_in.horiz_accuracy; - packet1.vert_accuracy = packet_in.vert_accuracy; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_WIND_COV_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_WIND_COV_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_wind_cov_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_wind_cov_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_wind_cov_pack(system_id, component_id, &msg , packet1.time_usec , packet1.wind_x , packet1.wind_y , packet1.wind_z , packet1.var_horiz , packet1.var_vert , packet1.wind_alt , packet1.horiz_accuracy , packet1.vert_accuracy ); - mavlink_msg_wind_cov_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_wind_cov_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.wind_x , packet1.wind_y , packet1.wind_z , packet1.var_horiz , packet1.var_vert , packet1.wind_alt , packet1.horiz_accuracy , packet1.vert_accuracy ); - mavlink_msg_wind_cov_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_GPS_INPUT >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_gps_input_t packet_in = { - 93372036854775807ULL,963497880,963498088,963498296,157.0,185.0,213.0,241.0,269.0,297.0,325.0,353.0,381.0,20147,20251,185,252,63,20511 - }; - mavlink_gps_input_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_usec = packet_in.time_usec; - packet1.time_week_ms = packet_in.time_week_ms; - packet1.lat = packet_in.lat; - packet1.lon = packet_in.lon; - packet1.alt = packet_in.alt; - packet1.hdop = packet_in.hdop; - packet1.vdop = packet_in.vdop; - packet1.vn = packet_in.vn; - packet1.ve = packet_in.ve; - packet1.vd = packet_in.vd; - packet1.speed_accuracy = packet_in.speed_accuracy; - packet1.horiz_accuracy = packet_in.horiz_accuracy; - packet1.vert_accuracy = packet_in.vert_accuracy; - packet1.ignore_flags = packet_in.ignore_flags; - packet1.time_week = packet_in.time_week; - packet1.gps_id = packet_in.gps_id; - packet1.fix_type = packet_in.fix_type; - packet1.satellites_visible = packet_in.satellites_visible; - packet1.yaw = packet_in.yaw; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_GPS_INPUT_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_GPS_INPUT_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_gps_input_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_gps_input_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_gps_input_pack(system_id, component_id, &msg , packet1.time_usec , packet1.gps_id , packet1.ignore_flags , packet1.time_week_ms , packet1.time_week , packet1.fix_type , packet1.lat , packet1.lon , packet1.alt , packet1.hdop , packet1.vdop , packet1.vn , packet1.ve , packet1.vd , packet1.speed_accuracy , packet1.horiz_accuracy , packet1.vert_accuracy , packet1.satellites_visible , packet1.yaw ); - mavlink_msg_gps_input_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_gps_input_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.gps_id , packet1.ignore_flags , packet1.time_week_ms , packet1.time_week , packet1.fix_type , packet1.lat , packet1.lon , packet1.alt , packet1.hdop , packet1.vdop , packet1.vn , packet1.ve , packet1.vd , packet1.speed_accuracy , packet1.horiz_accuracy , packet1.vert_accuracy , packet1.satellites_visible , packet1.yaw ); - mavlink_msg_gps_input_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_GPS_RTCM_DATA >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_gps_rtcm_data_t packet_in = { - 5,72,{ 139, 140, 141, 142, 143, 144, 145, 146, 147, 148, 149, 150, 151, 152, 153, 154, 155, 156, 157, 158, 159, 160, 161, 162, 163, 164, 165, 166, 167, 168, 169, 170, 171, 172, 173, 174, 175, 176, 177, 178, 179, 180, 181, 182, 183, 184, 185, 186, 187, 188, 189, 190, 191, 192, 193, 194, 195, 196, 197, 198, 199, 200, 201, 202, 203, 204, 205, 206, 207, 208, 209, 210, 211, 212, 213, 214, 215, 216, 217, 218, 219, 220, 221, 222, 223, 224, 225, 226, 227, 228, 229, 230, 231, 232, 233, 234, 235, 236, 237, 238, 239, 240, 241, 242, 243, 244, 245, 246, 247, 248, 249, 250, 251, 252, 253, 254, 255, 0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31, 32, 33, 34, 35, 36, 37, 38, 39, 40, 41, 42, 43, 44, 45, 46, 47, 48, 49, 50, 51, 52, 53, 54, 55, 56, 57, 58, 59, 60, 61, 62 } - }; - mavlink_gps_rtcm_data_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.flags = packet_in.flags; - packet1.len = packet_in.len; - - mav_array_memcpy(packet1.data, packet_in.data, sizeof(uint8_t)*180); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_GPS_RTCM_DATA_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_GPS_RTCM_DATA_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_gps_rtcm_data_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_gps_rtcm_data_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_gps_rtcm_data_pack(system_id, component_id, &msg , packet1.flags , packet1.len , packet1.data ); - mavlink_msg_gps_rtcm_data_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_gps_rtcm_data_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.flags , packet1.len , packet1.data ); - mavlink_msg_gps_rtcm_data_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_HIGH_LATENCY >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_high_latency_t packet_in = { - 963497464,963497672,963497880,17859,17963,18067,18171,18275,18379,18483,211,22,89,156,223,34,101,168,235,46,113,180,247,58 - }; - mavlink_high_latency_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.custom_mode = packet_in.custom_mode; - packet1.latitude = packet_in.latitude; - packet1.longitude = packet_in.longitude; - packet1.roll = packet_in.roll; - packet1.pitch = packet_in.pitch; - packet1.heading = packet_in.heading; - packet1.heading_sp = packet_in.heading_sp; - packet1.altitude_amsl = packet_in.altitude_amsl; - packet1.altitude_sp = packet_in.altitude_sp; - packet1.wp_distance = packet_in.wp_distance; - packet1.base_mode = packet_in.base_mode; - packet1.landed_state = packet_in.landed_state; - packet1.throttle = packet_in.throttle; - packet1.airspeed = packet_in.airspeed; - packet1.airspeed_sp = packet_in.airspeed_sp; - packet1.groundspeed = packet_in.groundspeed; - packet1.climb_rate = packet_in.climb_rate; - packet1.gps_nsat = packet_in.gps_nsat; - packet1.gps_fix_type = packet_in.gps_fix_type; - packet1.battery_remaining = packet_in.battery_remaining; - packet1.temperature = packet_in.temperature; - packet1.temperature_air = packet_in.temperature_air; - packet1.failsafe = packet_in.failsafe; - packet1.wp_num = packet_in.wp_num; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_HIGH_LATENCY_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_HIGH_LATENCY_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_high_latency_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_high_latency_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_high_latency_pack(system_id, component_id, &msg , packet1.base_mode , packet1.custom_mode , packet1.landed_state , packet1.roll , packet1.pitch , packet1.heading , packet1.throttle , packet1.heading_sp , packet1.latitude , packet1.longitude , packet1.altitude_amsl , packet1.altitude_sp , packet1.airspeed , packet1.airspeed_sp , packet1.groundspeed , packet1.climb_rate , packet1.gps_nsat , packet1.gps_fix_type , packet1.battery_remaining , packet1.temperature , packet1.temperature_air , packet1.failsafe , packet1.wp_num , packet1.wp_distance ); - mavlink_msg_high_latency_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_high_latency_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.base_mode , packet1.custom_mode , packet1.landed_state , packet1.roll , packet1.pitch , packet1.heading , packet1.throttle , packet1.heading_sp , packet1.latitude , packet1.longitude , packet1.altitude_amsl , packet1.altitude_sp , packet1.airspeed , packet1.airspeed_sp , packet1.groundspeed , packet1.climb_rate , packet1.gps_nsat , packet1.gps_fix_type , packet1.battery_remaining , packet1.temperature , packet1.temperature_air , packet1.failsafe , packet1.wp_num , packet1.wp_distance ); - mavlink_msg_high_latency_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_HIGH_LATENCY2 >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_high_latency2_t packet_in = { - 963497464,963497672,963497880,17859,17963,18067,18171,18275,18379,77,144,211,22,89,156,223,34,101,168,235,46,113,180,247,58,125,192 - }; - mavlink_high_latency2_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.timestamp = packet_in.timestamp; - packet1.latitude = packet_in.latitude; - packet1.longitude = packet_in.longitude; - packet1.custom_mode = packet_in.custom_mode; - packet1.altitude = packet_in.altitude; - packet1.target_altitude = packet_in.target_altitude; - packet1.target_distance = packet_in.target_distance; - packet1.wp_num = packet_in.wp_num; - packet1.failure_flags = packet_in.failure_flags; - packet1.type = packet_in.type; - packet1.autopilot = packet_in.autopilot; - packet1.heading = packet_in.heading; - packet1.target_heading = packet_in.target_heading; - packet1.throttle = packet_in.throttle; - packet1.airspeed = packet_in.airspeed; - packet1.airspeed_sp = packet_in.airspeed_sp; - packet1.groundspeed = packet_in.groundspeed; - packet1.windspeed = packet_in.windspeed; - packet1.wind_heading = packet_in.wind_heading; - packet1.eph = packet_in.eph; - packet1.epv = packet_in.epv; - packet1.temperature_air = packet_in.temperature_air; - packet1.climb_rate = packet_in.climb_rate; - packet1.battery = packet_in.battery; - packet1.custom0 = packet_in.custom0; - packet1.custom1 = packet_in.custom1; - packet1.custom2 = packet_in.custom2; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_HIGH_LATENCY2_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_HIGH_LATENCY2_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_high_latency2_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_high_latency2_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_high_latency2_pack(system_id, component_id, &msg , packet1.timestamp , packet1.type , packet1.autopilot , packet1.custom_mode , packet1.latitude , packet1.longitude , packet1.altitude , packet1.target_altitude , packet1.heading , packet1.target_heading , packet1.target_distance , packet1.throttle , packet1.airspeed , packet1.airspeed_sp , packet1.groundspeed , packet1.windspeed , packet1.wind_heading , packet1.eph , packet1.epv , packet1.temperature_air , packet1.climb_rate , packet1.battery , packet1.wp_num , packet1.failure_flags , packet1.custom0 , packet1.custom1 , packet1.custom2 ); - mavlink_msg_high_latency2_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_high_latency2_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.type , packet1.autopilot , packet1.custom_mode , packet1.latitude , packet1.longitude , packet1.altitude , packet1.target_altitude , packet1.heading , packet1.target_heading , packet1.target_distance , packet1.throttle , packet1.airspeed , packet1.airspeed_sp , packet1.groundspeed , packet1.windspeed , packet1.wind_heading , packet1.eph , packet1.epv , packet1.temperature_air , packet1.climb_rate , packet1.battery , packet1.wp_num , packet1.failure_flags , packet1.custom0 , packet1.custom1 , packet1.custom2 ); - mavlink_msg_high_latency2_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_VIBRATION >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_vibration_t packet_in = { - 93372036854775807ULL,73.0,101.0,129.0,963498504,963498712,963498920 - }; - mavlink_vibration_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_usec = packet_in.time_usec; - packet1.vibration_x = packet_in.vibration_x; - packet1.vibration_y = packet_in.vibration_y; - packet1.vibration_z = packet_in.vibration_z; - packet1.clipping_0 = packet_in.clipping_0; - packet1.clipping_1 = packet_in.clipping_1; - packet1.clipping_2 = packet_in.clipping_2; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_VIBRATION_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_VIBRATION_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_vibration_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_vibration_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_vibration_pack(system_id, component_id, &msg , packet1.time_usec , packet1.vibration_x , packet1.vibration_y , packet1.vibration_z , packet1.clipping_0 , packet1.clipping_1 , packet1.clipping_2 ); - mavlink_msg_vibration_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_vibration_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.vibration_x , packet1.vibration_y , packet1.vibration_z , packet1.clipping_0 , packet1.clipping_1 , packet1.clipping_2 ); - mavlink_msg_vibration_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_HOME_POSITION >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_home_position_t packet_in = { - 963497464,963497672,963497880,101.0,129.0,157.0,{ 185.0, 186.0, 187.0, 188.0 },297.0,325.0,353.0,93372036854779083ULL - }; - mavlink_home_position_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.latitude = packet_in.latitude; - packet1.longitude = packet_in.longitude; - packet1.altitude = packet_in.altitude; - packet1.x = packet_in.x; - packet1.y = packet_in.y; - packet1.z = packet_in.z; - packet1.approach_x = packet_in.approach_x; - packet1.approach_y = packet_in.approach_y; - packet1.approach_z = packet_in.approach_z; - packet1.time_usec = packet_in.time_usec; - - mav_array_memcpy(packet1.q, packet_in.q, sizeof(float)*4); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_HOME_POSITION_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_HOME_POSITION_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_home_position_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_home_position_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_home_position_pack(system_id, component_id, &msg , packet1.latitude , packet1.longitude , packet1.altitude , packet1.x , packet1.y , packet1.z , packet1.q , packet1.approach_x , packet1.approach_y , packet1.approach_z , packet1.time_usec ); - mavlink_msg_home_position_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_home_position_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.latitude , packet1.longitude , packet1.altitude , packet1.x , packet1.y , packet1.z , packet1.q , packet1.approach_x , packet1.approach_y , packet1.approach_z , packet1.time_usec ); - mavlink_msg_home_position_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_SET_HOME_POSITION >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_set_home_position_t packet_in = { - 963497464,963497672,963497880,101.0,129.0,157.0,{ 185.0, 186.0, 187.0, 188.0 },297.0,325.0,353.0,161,93372036854779146ULL - }; - mavlink_set_home_position_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.latitude = packet_in.latitude; - packet1.longitude = packet_in.longitude; - packet1.altitude = packet_in.altitude; - packet1.x = packet_in.x; - packet1.y = packet_in.y; - packet1.z = packet_in.z; - packet1.approach_x = packet_in.approach_x; - packet1.approach_y = packet_in.approach_y; - packet1.approach_z = packet_in.approach_z; - packet1.target_system = packet_in.target_system; - packet1.time_usec = packet_in.time_usec; - - mav_array_memcpy(packet1.q, packet_in.q, sizeof(float)*4); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_SET_HOME_POSITION_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SET_HOME_POSITION_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_set_home_position_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_set_home_position_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_set_home_position_pack(system_id, component_id, &msg , packet1.target_system , packet1.latitude , packet1.longitude , packet1.altitude , packet1.x , packet1.y , packet1.z , packet1.q , packet1.approach_x , packet1.approach_y , packet1.approach_z , packet1.time_usec ); - mavlink_msg_set_home_position_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_set_home_position_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.latitude , packet1.longitude , packet1.altitude , packet1.x , packet1.y , packet1.z , packet1.q , packet1.approach_x , packet1.approach_y , packet1.approach_z , packet1.time_usec ); - mavlink_msg_set_home_position_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_MESSAGE_INTERVAL >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_message_interval_t packet_in = { - 963497464,17443 - }; - mavlink_message_interval_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.interval_us = packet_in.interval_us; - packet1.message_id = packet_in.message_id; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_MESSAGE_INTERVAL_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_MESSAGE_INTERVAL_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_message_interval_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_message_interval_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_message_interval_pack(system_id, component_id, &msg , packet1.message_id , packet1.interval_us ); - mavlink_msg_message_interval_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_message_interval_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.message_id , packet1.interval_us ); - mavlink_msg_message_interval_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_EXTENDED_SYS_STATE >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_extended_sys_state_t packet_in = { - 5,72 - }; - mavlink_extended_sys_state_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.vtol_state = packet_in.vtol_state; - packet1.landed_state = packet_in.landed_state; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_EXTENDED_SYS_STATE_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_EXTENDED_SYS_STATE_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_extended_sys_state_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_extended_sys_state_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_extended_sys_state_pack(system_id, component_id, &msg , packet1.vtol_state , packet1.landed_state ); - mavlink_msg_extended_sys_state_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_extended_sys_state_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.vtol_state , packet1.landed_state ); - mavlink_msg_extended_sys_state_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_ADSB_VEHICLE >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_adsb_vehicle_t packet_in = { - 963497464,963497672,963497880,963498088,18067,18171,18275,18379,18483,211,"BCDEFGHI",113,180 - }; - mavlink_adsb_vehicle_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.ICAO_address = packet_in.ICAO_address; - packet1.lat = packet_in.lat; - packet1.lon = packet_in.lon; - packet1.altitude = packet_in.altitude; - packet1.heading = packet_in.heading; - packet1.hor_velocity = packet_in.hor_velocity; - packet1.ver_velocity = packet_in.ver_velocity; - packet1.flags = packet_in.flags; - packet1.squawk = packet_in.squawk; - packet1.altitude_type = packet_in.altitude_type; - packet1.emitter_type = packet_in.emitter_type; - packet1.tslc = packet_in.tslc; - - mav_array_memcpy(packet1.callsign, packet_in.callsign, sizeof(char)*9); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_ADSB_VEHICLE_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_ADSB_VEHICLE_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_adsb_vehicle_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_adsb_vehicle_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_adsb_vehicle_pack(system_id, component_id, &msg , packet1.ICAO_address , packet1.lat , packet1.lon , packet1.altitude_type , packet1.altitude , packet1.heading , packet1.hor_velocity , packet1.ver_velocity , packet1.callsign , packet1.emitter_type , packet1.tslc , packet1.flags , packet1.squawk ); - mavlink_msg_adsb_vehicle_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_adsb_vehicle_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.ICAO_address , packet1.lat , packet1.lon , packet1.altitude_type , packet1.altitude , packet1.heading , packet1.hor_velocity , packet1.ver_velocity , packet1.callsign , packet1.emitter_type , packet1.tslc , packet1.flags , packet1.squawk ); - mavlink_msg_adsb_vehicle_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_COLLISION >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_collision_t packet_in = { - 963497464,45.0,73.0,101.0,53,120,187 - }; - mavlink_collision_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.id = packet_in.id; - packet1.time_to_minimum_delta = packet_in.time_to_minimum_delta; - packet1.altitude_minimum_delta = packet_in.altitude_minimum_delta; - packet1.horizontal_minimum_delta = packet_in.horizontal_minimum_delta; - packet1.src = packet_in.src; - packet1.action = packet_in.action; - packet1.threat_level = packet_in.threat_level; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_COLLISION_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_COLLISION_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_collision_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_collision_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_collision_pack(system_id, component_id, &msg , packet1.src , packet1.id , packet1.action , packet1.threat_level , packet1.time_to_minimum_delta , packet1.altitude_minimum_delta , packet1.horizontal_minimum_delta ); - mavlink_msg_collision_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_collision_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.src , packet1.id , packet1.action , packet1.threat_level , packet1.time_to_minimum_delta , packet1.altitude_minimum_delta , packet1.horizontal_minimum_delta ); - mavlink_msg_collision_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_V2_EXTENSION >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_v2_extension_t packet_in = { - 17235,139,206,17,{ 84, 85, 86, 87, 88, 89, 90, 91, 92, 93, 94, 95, 96, 97, 98, 99, 100, 101, 102, 103, 104, 105, 106, 107, 108, 109, 110, 111, 112, 113, 114, 115, 116, 117, 118, 119, 120, 121, 122, 123, 124, 125, 126, 127, 128, 129, 130, 131, 132, 133, 134, 135, 136, 137, 138, 139, 140, 141, 142, 143, 144, 145, 146, 147, 148, 149, 150, 151, 152, 153, 154, 155, 156, 157, 158, 159, 160, 161, 162, 163, 164, 165, 166, 167, 168, 169, 170, 171, 172, 173, 174, 175, 176, 177, 178, 179, 180, 181, 182, 183, 184, 185, 186, 187, 188, 189, 190, 191, 192, 193, 194, 195, 196, 197, 198, 199, 200, 201, 202, 203, 204, 205, 206, 207, 208, 209, 210, 211, 212, 213, 214, 215, 216, 217, 218, 219, 220, 221, 222, 223, 224, 225, 226, 227, 228, 229, 230, 231, 232, 233, 234, 235, 236, 237, 238, 239, 240, 241, 242, 243, 244, 245, 246, 247, 248, 249, 250, 251, 252, 253, 254, 255, 0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31, 32, 33, 34, 35, 36, 37, 38, 39, 40, 41, 42, 43, 44, 45, 46, 47, 48, 49, 50, 51, 52, 53, 54, 55, 56, 57, 58, 59, 60, 61, 62, 63, 64, 65, 66, 67, 68, 69, 70, 71, 72, 73, 74, 75, 76 } - }; - mavlink_v2_extension_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.message_type = packet_in.message_type; - packet1.target_network = packet_in.target_network; - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - - mav_array_memcpy(packet1.payload, packet_in.payload, sizeof(uint8_t)*249); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_V2_EXTENSION_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_V2_EXTENSION_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_v2_extension_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_v2_extension_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_v2_extension_pack(system_id, component_id, &msg , packet1.target_network , packet1.target_system , packet1.target_component , packet1.message_type , packet1.payload ); - mavlink_msg_v2_extension_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_v2_extension_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_network , packet1.target_system , packet1.target_component , packet1.message_type , packet1.payload ); - mavlink_msg_v2_extension_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_MEMORY_VECT >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_memory_vect_t packet_in = { - 17235,139,206,{ 17, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31, 32, 33, 34, 35, 36, 37, 38, 39, 40, 41, 42, 43, 44, 45, 46, 47, 48 } - }; - mavlink_memory_vect_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.address = packet_in.address; - packet1.ver = packet_in.ver; - packet1.type = packet_in.type; - - mav_array_memcpy(packet1.value, packet_in.value, sizeof(int8_t)*32); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_MEMORY_VECT_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_MEMORY_VECT_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_memory_vect_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_memory_vect_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_memory_vect_pack(system_id, component_id, &msg , packet1.address , packet1.ver , packet1.type , packet1.value ); - mavlink_msg_memory_vect_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_memory_vect_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.address , packet1.ver , packet1.type , packet1.value ); - mavlink_msg_memory_vect_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_DEBUG_VECT >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_debug_vect_t packet_in = { - 93372036854775807ULL,73.0,101.0,129.0,"UVWXYZABC" - }; - mavlink_debug_vect_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_usec = packet_in.time_usec; - packet1.x = packet_in.x; - packet1.y = packet_in.y; - packet1.z = packet_in.z; - - mav_array_memcpy(packet1.name, packet_in.name, sizeof(char)*10); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_DEBUG_VECT_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_DEBUG_VECT_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_debug_vect_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_debug_vect_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_debug_vect_pack(system_id, component_id, &msg , packet1.name , packet1.time_usec , packet1.x , packet1.y , packet1.z ); - mavlink_msg_debug_vect_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_debug_vect_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.name , packet1.time_usec , packet1.x , packet1.y , packet1.z ); - mavlink_msg_debug_vect_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_NAMED_VALUE_FLOAT >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_named_value_float_t packet_in = { - 963497464,45.0,"IJKLMNOPQ" - }; - mavlink_named_value_float_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_boot_ms = packet_in.time_boot_ms; - packet1.value = packet_in.value; - - mav_array_memcpy(packet1.name, packet_in.name, sizeof(char)*10); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_named_value_float_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_named_value_float_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_named_value_float_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.name , packet1.value ); - mavlink_msg_named_value_float_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_named_value_float_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.name , packet1.value ); - mavlink_msg_named_value_float_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_NAMED_VALUE_INT >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_named_value_int_t packet_in = { - 963497464,963497672,"IJKLMNOPQ" - }; - mavlink_named_value_int_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_boot_ms = packet_in.time_boot_ms; - packet1.value = packet_in.value; - - mav_array_memcpy(packet1.name, packet_in.name, sizeof(char)*10); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_NAMED_VALUE_INT_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_NAMED_VALUE_INT_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_named_value_int_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_named_value_int_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_named_value_int_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.name , packet1.value ); - mavlink_msg_named_value_int_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_named_value_int_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.name , packet1.value ); - mavlink_msg_named_value_int_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_STATUSTEXT >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_statustext_t packet_in = { - 5,"BCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWX",19887,228 - }; - mavlink_statustext_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.severity = packet_in.severity; - packet1.id = packet_in.id; - packet1.chunk_seq = packet_in.chunk_seq; - - mav_array_memcpy(packet1.text, packet_in.text, sizeof(char)*50); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_STATUSTEXT_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_STATUSTEXT_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_statustext_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_statustext_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_statustext_pack(system_id, component_id, &msg , packet1.severity , packet1.text , packet1.id , packet1.chunk_seq ); - mavlink_msg_statustext_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_statustext_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.severity , packet1.text , packet1.id , packet1.chunk_seq ); - mavlink_msg_statustext_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_DEBUG >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_debug_t packet_in = { - 963497464,45.0,29 - }; - mavlink_debug_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_boot_ms = packet_in.time_boot_ms; - packet1.value = packet_in.value; - packet1.ind = packet_in.ind; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_DEBUG_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_DEBUG_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_debug_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_debug_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_debug_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.ind , packet1.value ); - mavlink_msg_debug_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_debug_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.ind , packet1.value ); - mavlink_msg_debug_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_SETUP_SIGNING >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_setup_signing_t packet_in = { - 93372036854775807ULL,29,96,{ 163, 164, 165, 166, 167, 168, 169, 170, 171, 172, 173, 174, 175, 176, 177, 178, 179, 180, 181, 182, 183, 184, 185, 186, 187, 188, 189, 190, 191, 192, 193, 194 } - }; - mavlink_setup_signing_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.initial_timestamp = packet_in.initial_timestamp; - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - - mav_array_memcpy(packet1.secret_key, packet_in.secret_key, sizeof(uint8_t)*32); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_SETUP_SIGNING_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SETUP_SIGNING_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_setup_signing_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_setup_signing_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_setup_signing_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.secret_key , packet1.initial_timestamp ); - mavlink_msg_setup_signing_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_setup_signing_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.secret_key , packet1.initial_timestamp ); - mavlink_msg_setup_signing_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_BUTTON_CHANGE >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_button_change_t packet_in = { - 963497464,963497672,29 - }; - mavlink_button_change_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_boot_ms = packet_in.time_boot_ms; - packet1.last_change_ms = packet_in.last_change_ms; - packet1.state = packet_in.state; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_BUTTON_CHANGE_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_BUTTON_CHANGE_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_button_change_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_button_change_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_button_change_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.last_change_ms , packet1.state ); - mavlink_msg_button_change_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_button_change_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.last_change_ms , packet1.state ); - mavlink_msg_button_change_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_PLAY_TUNE >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_play_tune_t packet_in = { - 5,72,"CDEFGHIJKLMNOPQRSTUVWXYZABCDE","GHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVW" - }; - mavlink_play_tune_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - - mav_array_memcpy(packet1.tune, packet_in.tune, sizeof(char)*30); - mav_array_memcpy(packet1.tune2, packet_in.tune2, sizeof(char)*200); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_PLAY_TUNE_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_PLAY_TUNE_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_play_tune_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_play_tune_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_play_tune_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.tune , packet1.tune2 ); - mavlink_msg_play_tune_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_play_tune_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.tune , packet1.tune2 ); - mavlink_msg_play_tune_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_CAMERA_INFORMATION >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_camera_information_t packet_in = { - 963497464,963497672,73.0,101.0,129.0,963498504,18483,18587,18691,{ 223, 224, 225, 226, 227, 228, 229, 230, 231, 232, 233, 234, 235, 236, 237, 238, 239, 240, 241, 242, 243, 244, 245, 246, 247, 248, 249, 250, 251, 252, 253, 254 },{ 63, 64, 65, 66, 67, 68, 69, 70, 71, 72, 73, 74, 75, 76, 77, 78, 79, 80, 81, 82, 83, 84, 85, 86, 87, 88, 89, 90, 91, 92, 93, 94 },159,"RSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZ",134 - }; - mavlink_camera_information_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_boot_ms = packet_in.time_boot_ms; - packet1.firmware_version = packet_in.firmware_version; - packet1.focal_length = packet_in.focal_length; - packet1.sensor_size_h = packet_in.sensor_size_h; - packet1.sensor_size_v = packet_in.sensor_size_v; - packet1.flags = packet_in.flags; - packet1.resolution_h = packet_in.resolution_h; - packet1.resolution_v = packet_in.resolution_v; - packet1.cam_definition_version = packet_in.cam_definition_version; - packet1.lens_id = packet_in.lens_id; - packet1.gimbal_device_id = packet_in.gimbal_device_id; - - mav_array_memcpy(packet1.vendor_name, packet_in.vendor_name, sizeof(uint8_t)*32); - mav_array_memcpy(packet1.model_name, packet_in.model_name, sizeof(uint8_t)*32); - mav_array_memcpy(packet1.cam_definition_uri, packet_in.cam_definition_uri, sizeof(char)*140); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_CAMERA_INFORMATION_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_CAMERA_INFORMATION_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_camera_information_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_camera_information_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_camera_information_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.vendor_name , packet1.model_name , packet1.firmware_version , packet1.focal_length , packet1.sensor_size_h , packet1.sensor_size_v , packet1.resolution_h , packet1.resolution_v , packet1.lens_id , packet1.flags , packet1.cam_definition_version , packet1.cam_definition_uri , packet1.gimbal_device_id ); - mavlink_msg_camera_information_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_camera_information_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.vendor_name , packet1.model_name , packet1.firmware_version , packet1.focal_length , packet1.sensor_size_h , packet1.sensor_size_v , packet1.resolution_h , packet1.resolution_v , packet1.lens_id , packet1.flags , packet1.cam_definition_version , packet1.cam_definition_uri , packet1.gimbal_device_id ); - mavlink_msg_camera_information_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_CAMERA_SETTINGS >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_camera_settings_t packet_in = { - 963497464,17,52.0,80.0 - }; - mavlink_camera_settings_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_boot_ms = packet_in.time_boot_ms; - packet1.mode_id = packet_in.mode_id; - packet1.zoomLevel = packet_in.zoomLevel; - packet1.focusLevel = packet_in.focusLevel; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_CAMERA_SETTINGS_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_CAMERA_SETTINGS_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_camera_settings_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_camera_settings_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_camera_settings_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.mode_id , packet1.zoomLevel , packet1.focusLevel ); - mavlink_msg_camera_settings_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_camera_settings_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.mode_id , packet1.zoomLevel , packet1.focusLevel ); - mavlink_msg_camera_settings_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_STORAGE_INFORMATION >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_storage_information_t packet_in = { - 963497464,45.0,73.0,101.0,129.0,157.0,77,144,211,22,"CDEFGHIJKLMNOPQRSTUVWXYZABCDEFG",185 - }; - mavlink_storage_information_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_boot_ms = packet_in.time_boot_ms; - packet1.total_capacity = packet_in.total_capacity; - packet1.used_capacity = packet_in.used_capacity; - packet1.available_capacity = packet_in.available_capacity; - packet1.read_speed = packet_in.read_speed; - packet1.write_speed = packet_in.write_speed; - packet1.storage_id = packet_in.storage_id; - packet1.storage_count = packet_in.storage_count; - packet1.status = packet_in.status; - packet1.type = packet_in.type; - packet1.storage_usage = packet_in.storage_usage; - - mav_array_memcpy(packet1.name, packet_in.name, sizeof(char)*32); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_STORAGE_INFORMATION_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_STORAGE_INFORMATION_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_storage_information_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_storage_information_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_storage_information_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.storage_id , packet1.storage_count , packet1.status , packet1.total_capacity , packet1.used_capacity , packet1.available_capacity , packet1.read_speed , packet1.write_speed , packet1.type , packet1.name , packet1.storage_usage ); - mavlink_msg_storage_information_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_storage_information_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.storage_id , packet1.storage_count , packet1.status , packet1.total_capacity , packet1.used_capacity , packet1.available_capacity , packet1.read_speed , packet1.write_speed , packet1.type , packet1.name , packet1.storage_usage ); - mavlink_msg_storage_information_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_camera_capture_status_t packet_in = { - 963497464,45.0,963497880,101.0,53,120,963498400 - }; - mavlink_camera_capture_status_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_boot_ms = packet_in.time_boot_ms; - packet1.image_interval = packet_in.image_interval; - packet1.recording_time_ms = packet_in.recording_time_ms; - packet1.available_capacity = packet_in.available_capacity; - packet1.image_status = packet_in.image_status; - packet1.video_status = packet_in.video_status; - packet1.image_count = packet_in.image_count; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_camera_capture_status_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_camera_capture_status_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_camera_capture_status_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.image_status , packet1.video_status , packet1.image_interval , packet1.recording_time_ms , packet1.available_capacity , packet1.image_count ); - mavlink_msg_camera_capture_status_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_camera_capture_status_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.image_status , packet1.video_status , packet1.image_interval , packet1.recording_time_ms , packet1.available_capacity , packet1.image_count ); - mavlink_msg_camera_capture_status_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_camera_image_captured_t packet_in = { - 93372036854775807ULL,963497880,963498088,963498296,963498504,963498712,{ 213.0, 214.0, 215.0, 216.0 },963499752,149,216,"YZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRST" - }; - mavlink_camera_image_captured_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_utc = packet_in.time_utc; - packet1.time_boot_ms = packet_in.time_boot_ms; - packet1.lat = packet_in.lat; - packet1.lon = packet_in.lon; - packet1.alt = packet_in.alt; - packet1.relative_alt = packet_in.relative_alt; - packet1.image_index = packet_in.image_index; - packet1.camera_id = packet_in.camera_id; - packet1.capture_result = packet_in.capture_result; - - mav_array_memcpy(packet1.q, packet_in.q, sizeof(float)*4); - mav_array_memcpy(packet1.file_url, packet_in.file_url, sizeof(char)*205); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_camera_image_captured_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_camera_image_captured_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_camera_image_captured_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.time_utc , packet1.camera_id , packet1.lat , packet1.lon , packet1.alt , packet1.relative_alt , packet1.q , packet1.image_index , packet1.capture_result , packet1.file_url ); - mavlink_msg_camera_image_captured_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_camera_image_captured_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.time_utc , packet1.camera_id , packet1.lat , packet1.lon , packet1.alt , packet1.relative_alt , packet1.q , packet1.image_index , packet1.capture_result , packet1.file_url ); - mavlink_msg_camera_image_captured_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_FLIGHT_INFORMATION >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_flight_information_t packet_in = { - 93372036854775807ULL,93372036854776311ULL,93372036854776815ULL,963498712 - }; - mavlink_flight_information_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.arming_time_utc = packet_in.arming_time_utc; - packet1.takeoff_time_utc = packet_in.takeoff_time_utc; - packet1.flight_uuid = packet_in.flight_uuid; - packet1.time_boot_ms = packet_in.time_boot_ms; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_FLIGHT_INFORMATION_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_FLIGHT_INFORMATION_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_flight_information_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_flight_information_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_flight_information_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.arming_time_utc , packet1.takeoff_time_utc , packet1.flight_uuid ); - mavlink_msg_flight_information_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_flight_information_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.arming_time_utc , packet1.takeoff_time_utc , packet1.flight_uuid ); - mavlink_msg_flight_information_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_MOUNT_ORIENTATION >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_mount_orientation_t packet_in = { - 963497464,45.0,73.0,101.0,129.0 - }; - mavlink_mount_orientation_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_boot_ms = packet_in.time_boot_ms; - packet1.roll = packet_in.roll; - packet1.pitch = packet_in.pitch; - packet1.yaw = packet_in.yaw; - packet1.yaw_absolute = packet_in.yaw_absolute; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_MOUNT_ORIENTATION_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_MOUNT_ORIENTATION_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_mount_orientation_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_mount_orientation_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_mount_orientation_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.roll , packet1.pitch , packet1.yaw , packet1.yaw_absolute ); - mavlink_msg_mount_orientation_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_mount_orientation_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.roll , packet1.pitch , packet1.yaw , packet1.yaw_absolute ); - mavlink_msg_mount_orientation_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_LOGGING_DATA >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_logging_data_t packet_in = { - 17235,139,206,17,84,{ 151, 152, 153, 154, 155, 156, 157, 158, 159, 160, 161, 162, 163, 164, 165, 166, 167, 168, 169, 170, 171, 172, 173, 174, 175, 176, 177, 178, 179, 180, 181, 182, 183, 184, 185, 186, 187, 188, 189, 190, 191, 192, 193, 194, 195, 196, 197, 198, 199, 200, 201, 202, 203, 204, 205, 206, 207, 208, 209, 210, 211, 212, 213, 214, 215, 216, 217, 218, 219, 220, 221, 222, 223, 224, 225, 226, 227, 228, 229, 230, 231, 232, 233, 234, 235, 236, 237, 238, 239, 240, 241, 242, 243, 244, 245, 246, 247, 248, 249, 250, 251, 252, 253, 254, 255, 0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31, 32, 33, 34, 35, 36, 37, 38, 39, 40, 41, 42, 43, 44, 45, 46, 47, 48, 49, 50, 51, 52, 53, 54, 55, 56, 57, 58, 59, 60, 61, 62, 63, 64, 65, 66, 67, 68, 69, 70, 71, 72, 73, 74, 75, 76, 77, 78, 79, 80, 81, 82, 83, 84, 85, 86, 87, 88, 89, 90, 91, 92, 93, 94, 95, 96, 97, 98, 99, 100, 101, 102, 103, 104, 105, 106, 107, 108, 109, 110, 111, 112, 113, 114, 115, 116, 117, 118, 119, 120, 121, 122, 123, 124, 125, 126, 127, 128, 129, 130, 131, 132, 133, 134, 135, 136, 137, 138, 139, 140, 141, 142, 143 } - }; - mavlink_logging_data_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.sequence = packet_in.sequence; - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - packet1.length = packet_in.length; - packet1.first_message_offset = packet_in.first_message_offset; - - mav_array_memcpy(packet1.data, packet_in.data, sizeof(uint8_t)*249); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_LOGGING_DATA_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_LOGGING_DATA_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_logging_data_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_logging_data_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_logging_data_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.sequence , packet1.length , packet1.first_message_offset , packet1.data ); - mavlink_msg_logging_data_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_logging_data_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.sequence , packet1.length , packet1.first_message_offset , packet1.data ); - mavlink_msg_logging_data_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_LOGGING_DATA_ACKED >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_logging_data_acked_t packet_in = { - 17235,139,206,17,84,{ 151, 152, 153, 154, 155, 156, 157, 158, 159, 160, 161, 162, 163, 164, 165, 166, 167, 168, 169, 170, 171, 172, 173, 174, 175, 176, 177, 178, 179, 180, 181, 182, 183, 184, 185, 186, 187, 188, 189, 190, 191, 192, 193, 194, 195, 196, 197, 198, 199, 200, 201, 202, 203, 204, 205, 206, 207, 208, 209, 210, 211, 212, 213, 214, 215, 216, 217, 218, 219, 220, 221, 222, 223, 224, 225, 226, 227, 228, 229, 230, 231, 232, 233, 234, 235, 236, 237, 238, 239, 240, 241, 242, 243, 244, 245, 246, 247, 248, 249, 250, 251, 252, 253, 254, 255, 0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31, 32, 33, 34, 35, 36, 37, 38, 39, 40, 41, 42, 43, 44, 45, 46, 47, 48, 49, 50, 51, 52, 53, 54, 55, 56, 57, 58, 59, 60, 61, 62, 63, 64, 65, 66, 67, 68, 69, 70, 71, 72, 73, 74, 75, 76, 77, 78, 79, 80, 81, 82, 83, 84, 85, 86, 87, 88, 89, 90, 91, 92, 93, 94, 95, 96, 97, 98, 99, 100, 101, 102, 103, 104, 105, 106, 107, 108, 109, 110, 111, 112, 113, 114, 115, 116, 117, 118, 119, 120, 121, 122, 123, 124, 125, 126, 127, 128, 129, 130, 131, 132, 133, 134, 135, 136, 137, 138, 139, 140, 141, 142, 143 } - }; - mavlink_logging_data_acked_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.sequence = packet_in.sequence; - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - packet1.length = packet_in.length; - packet1.first_message_offset = packet_in.first_message_offset; - - mav_array_memcpy(packet1.data, packet_in.data, sizeof(uint8_t)*249); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_LOGGING_DATA_ACKED_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_LOGGING_DATA_ACKED_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_logging_data_acked_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_logging_data_acked_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_logging_data_acked_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.sequence , packet1.length , packet1.first_message_offset , packet1.data ); - mavlink_msg_logging_data_acked_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_logging_data_acked_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.sequence , packet1.length , packet1.first_message_offset , packet1.data ); - mavlink_msg_logging_data_acked_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_LOGGING_ACK >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_logging_ack_t packet_in = { - 17235,139,206 - }; - mavlink_logging_ack_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.sequence = packet_in.sequence; - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_LOGGING_ACK_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_LOGGING_ACK_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_logging_ack_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_logging_ack_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_logging_ack_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.sequence ); - mavlink_msg_logging_ack_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_logging_ack_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.sequence ); - mavlink_msg_logging_ack_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_video_stream_information_t packet_in = { - 17.0,963497672,17651,17755,17859,17963,18067,187,254,65,"VWXYZABCDEFGHIJKLMNOPQRSTUVWXYZ","BCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCD" - }; - mavlink_video_stream_information_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.framerate = packet_in.framerate; - packet1.bitrate = packet_in.bitrate; - packet1.flags = packet_in.flags; - packet1.resolution_h = packet_in.resolution_h; - packet1.resolution_v = packet_in.resolution_v; - packet1.rotation = packet_in.rotation; - packet1.hfov = packet_in.hfov; - packet1.stream_id = packet_in.stream_id; - packet1.count = packet_in.count; - packet1.type = packet_in.type; - - mav_array_memcpy(packet1.name, packet_in.name, sizeof(char)*32); - mav_array_memcpy(packet1.uri, packet_in.uri, sizeof(char)*160); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_video_stream_information_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_video_stream_information_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_video_stream_information_pack(system_id, component_id, &msg , packet1.stream_id , packet1.count , packet1.type , packet1.flags , packet1.framerate , packet1.resolution_h , packet1.resolution_v , packet1.bitrate , packet1.rotation , packet1.hfov , packet1.name , packet1.uri ); - mavlink_msg_video_stream_information_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_video_stream_information_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.stream_id , packet1.count , packet1.type , packet1.flags , packet1.framerate , packet1.resolution_h , packet1.resolution_v , packet1.bitrate , packet1.rotation , packet1.hfov , packet1.name , packet1.uri ); - mavlink_msg_video_stream_information_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_VIDEO_STREAM_STATUS >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_video_stream_status_t packet_in = { - 17.0,963497672,17651,17755,17859,17963,18067,187 - }; - mavlink_video_stream_status_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.framerate = packet_in.framerate; - packet1.bitrate = packet_in.bitrate; - packet1.flags = packet_in.flags; - packet1.resolution_h = packet_in.resolution_h; - packet1.resolution_v = packet_in.resolution_v; - packet1.rotation = packet_in.rotation; - packet1.hfov = packet_in.hfov; - packet1.stream_id = packet_in.stream_id; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_VIDEO_STREAM_STATUS_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_VIDEO_STREAM_STATUS_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_video_stream_status_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_video_stream_status_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_video_stream_status_pack(system_id, component_id, &msg , packet1.stream_id , packet1.flags , packet1.framerate , packet1.resolution_h , packet1.resolution_v , packet1.bitrate , packet1.rotation , packet1.hfov ); - mavlink_msg_video_stream_status_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_video_stream_status_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.stream_id , packet1.flags , packet1.framerate , packet1.resolution_h , packet1.resolution_v , packet1.bitrate , packet1.rotation , packet1.hfov ); - mavlink_msg_video_stream_status_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_CAMERA_FOV_STATUS >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_camera_fov_status_t packet_in = { - 963497464,963497672,963497880,963498088,963498296,963498504,963498712,{ 213.0, 214.0, 215.0, 216.0 },325.0,353.0 - }; - mavlink_camera_fov_status_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_boot_ms = packet_in.time_boot_ms; - packet1.lat_camera = packet_in.lat_camera; - packet1.lon_camera = packet_in.lon_camera; - packet1.alt_camera = packet_in.alt_camera; - packet1.lat_image = packet_in.lat_image; - packet1.lon_image = packet_in.lon_image; - packet1.alt_image = packet_in.alt_image; - packet1.hfov = packet_in.hfov; - packet1.vfov = packet_in.vfov; - - mav_array_memcpy(packet1.q, packet_in.q, sizeof(float)*4); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_CAMERA_FOV_STATUS_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_CAMERA_FOV_STATUS_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_camera_fov_status_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_camera_fov_status_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_camera_fov_status_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.lat_camera , packet1.lon_camera , packet1.alt_camera , packet1.lat_image , packet1.lon_image , packet1.alt_image , packet1.q , packet1.hfov , packet1.vfov ); - mavlink_msg_camera_fov_status_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_camera_fov_status_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.lat_camera , packet1.lon_camera , packet1.alt_camera , packet1.lat_image , packet1.lon_image , packet1.alt_image , packet1.q , packet1.hfov , packet1.vfov ); - mavlink_msg_camera_fov_status_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_camera_tracking_image_status_t packet_in = { - 17.0,45.0,73.0,101.0,129.0,157.0,185.0,89,156,223 - }; - mavlink_camera_tracking_image_status_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.point_x = packet_in.point_x; - packet1.point_y = packet_in.point_y; - packet1.radius = packet_in.radius; - packet1.rec_top_x = packet_in.rec_top_x; - packet1.rec_top_y = packet_in.rec_top_y; - packet1.rec_bottom_x = packet_in.rec_bottom_x; - packet1.rec_bottom_y = packet_in.rec_bottom_y; - packet1.tracking_status = packet_in.tracking_status; - packet1.tracking_mode = packet_in.tracking_mode; - packet1.target_data = packet_in.target_data; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_camera_tracking_image_status_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_camera_tracking_image_status_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_camera_tracking_image_status_pack(system_id, component_id, &msg , packet1.tracking_status , packet1.tracking_mode , packet1.target_data , packet1.point_x , packet1.point_y , packet1.radius , packet1.rec_top_x , packet1.rec_top_y , packet1.rec_bottom_x , packet1.rec_bottom_y ); - mavlink_msg_camera_tracking_image_status_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_camera_tracking_image_status_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.tracking_status , packet1.tracking_mode , packet1.target_data , packet1.point_x , packet1.point_y , packet1.radius , packet1.rec_top_x , packet1.rec_top_y , packet1.rec_bottom_x , packet1.rec_bottom_y ); - mavlink_msg_camera_tracking_image_status_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_CAMERA_TRACKING_GEO_STATUS >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_camera_tracking_geo_status_t packet_in = { - 963497464,963497672,73.0,101.0,129.0,157.0,185.0,213.0,241.0,269.0,297.0,325.0,149 - }; - mavlink_camera_tracking_geo_status_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.lat = packet_in.lat; - packet1.lon = packet_in.lon; - packet1.alt = packet_in.alt; - packet1.h_acc = packet_in.h_acc; - packet1.v_acc = packet_in.v_acc; - packet1.vel_n = packet_in.vel_n; - packet1.vel_e = packet_in.vel_e; - packet1.vel_d = packet_in.vel_d; - packet1.vel_acc = packet_in.vel_acc; - packet1.dist = packet_in.dist; - packet1.hdg = packet_in.hdg; - packet1.hdg_acc = packet_in.hdg_acc; - packet1.tracking_status = packet_in.tracking_status; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_CAMERA_TRACKING_GEO_STATUS_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_CAMERA_TRACKING_GEO_STATUS_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_camera_tracking_geo_status_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_camera_tracking_geo_status_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_camera_tracking_geo_status_pack(system_id, component_id, &msg , packet1.tracking_status , packet1.lat , packet1.lon , packet1.alt , packet1.h_acc , packet1.v_acc , packet1.vel_n , packet1.vel_e , packet1.vel_d , packet1.vel_acc , packet1.dist , packet1.hdg , packet1.hdg_acc ); - mavlink_msg_camera_tracking_geo_status_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_camera_tracking_geo_status_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.tracking_status , packet1.lat , packet1.lon , packet1.alt , packet1.h_acc , packet1.v_acc , packet1.vel_n , packet1.vel_e , packet1.vel_d , packet1.vel_acc , packet1.dist , packet1.hdg , packet1.hdg_acc ); - mavlink_msg_camera_tracking_geo_status_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_GIMBAL_MANAGER_INFORMATION >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_gimbal_manager_information_t packet_in = { - 963497464,963497672,73.0,101.0,129.0,157.0,185.0,213.0,101 - }; - mavlink_gimbal_manager_information_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_boot_ms = packet_in.time_boot_ms; - packet1.cap_flags = packet_in.cap_flags; - packet1.roll_min = packet_in.roll_min; - packet1.roll_max = packet_in.roll_max; - packet1.pitch_min = packet_in.pitch_min; - packet1.pitch_max = packet_in.pitch_max; - packet1.yaw_min = packet_in.yaw_min; - packet1.yaw_max = packet_in.yaw_max; - packet1.gimbal_device_id = packet_in.gimbal_device_id; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_GIMBAL_MANAGER_INFORMATION_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_GIMBAL_MANAGER_INFORMATION_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_gimbal_manager_information_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_gimbal_manager_information_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_gimbal_manager_information_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.cap_flags , packet1.gimbal_device_id , packet1.roll_min , packet1.roll_max , packet1.pitch_min , packet1.pitch_max , packet1.yaw_min , packet1.yaw_max ); - mavlink_msg_gimbal_manager_information_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_gimbal_manager_information_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.cap_flags , packet1.gimbal_device_id , packet1.roll_min , packet1.roll_max , packet1.pitch_min , packet1.pitch_max , packet1.yaw_min , packet1.yaw_max ); - mavlink_msg_gimbal_manager_information_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_GIMBAL_MANAGER_STATUS >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_gimbal_manager_status_t packet_in = { - 963497464,963497672,29,96,163,230,41 - }; - mavlink_gimbal_manager_status_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_boot_ms = packet_in.time_boot_ms; - packet1.flags = packet_in.flags; - packet1.gimbal_device_id = packet_in.gimbal_device_id; - packet1.primary_control_sysid = packet_in.primary_control_sysid; - packet1.primary_control_compid = packet_in.primary_control_compid; - packet1.secondary_control_sysid = packet_in.secondary_control_sysid; - packet1.secondary_control_compid = packet_in.secondary_control_compid; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_GIMBAL_MANAGER_STATUS_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_GIMBAL_MANAGER_STATUS_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_gimbal_manager_status_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_gimbal_manager_status_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_gimbal_manager_status_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.flags , packet1.gimbal_device_id , packet1.primary_control_sysid , packet1.primary_control_compid , packet1.secondary_control_sysid , packet1.secondary_control_compid ); - mavlink_msg_gimbal_manager_status_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_gimbal_manager_status_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.flags , packet1.gimbal_device_id , packet1.primary_control_sysid , packet1.primary_control_compid , packet1.secondary_control_sysid , packet1.secondary_control_compid ); - mavlink_msg_gimbal_manager_status_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_gimbal_manager_set_attitude_t packet_in = { - 963497464,{ 45.0, 46.0, 47.0, 48.0 },157.0,185.0,213.0,101,168,235 - }; - mavlink_gimbal_manager_set_attitude_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.flags = packet_in.flags; - packet1.angular_velocity_x = packet_in.angular_velocity_x; - packet1.angular_velocity_y = packet_in.angular_velocity_y; - packet1.angular_velocity_z = packet_in.angular_velocity_z; - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - packet1.gimbal_device_id = packet_in.gimbal_device_id; - - mav_array_memcpy(packet1.q, packet_in.q, sizeof(float)*4); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_gimbal_manager_set_attitude_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_gimbal_manager_set_attitude_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_gimbal_manager_set_attitude_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.flags , packet1.gimbal_device_id , packet1.q , packet1.angular_velocity_x , packet1.angular_velocity_y , packet1.angular_velocity_z ); - mavlink_msg_gimbal_manager_set_attitude_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_gimbal_manager_set_attitude_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.flags , packet1.gimbal_device_id , packet1.q , packet1.angular_velocity_x , packet1.angular_velocity_y , packet1.angular_velocity_z ); - mavlink_msg_gimbal_manager_set_attitude_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_gimbal_device_information_t packet_in = { - 93372036854775807ULL,963497880,963498088,963498296,157.0,185.0,213.0,241.0,269.0,297.0,19523,19627,"WXYZABCDEFGHIJKLMNOPQRSTUVWXYZA","CDEFGHIJKLMNOPQRSTUVWXYZABCDEFG","IJKLMNOPQRSTUVWXYZABCDEFGHIJKLM",181 - }; - mavlink_gimbal_device_information_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.uid = packet_in.uid; - packet1.time_boot_ms = packet_in.time_boot_ms; - packet1.firmware_version = packet_in.firmware_version; - packet1.hardware_version = packet_in.hardware_version; - packet1.roll_min = packet_in.roll_min; - packet1.roll_max = packet_in.roll_max; - packet1.pitch_min = packet_in.pitch_min; - packet1.pitch_max = packet_in.pitch_max; - packet1.yaw_min = packet_in.yaw_min; - packet1.yaw_max = packet_in.yaw_max; - packet1.cap_flags = packet_in.cap_flags; - packet1.custom_cap_flags = packet_in.custom_cap_flags; - packet1.gimbal_device_id = packet_in.gimbal_device_id; - - mav_array_memcpy(packet1.vendor_name, packet_in.vendor_name, sizeof(char)*32); - mav_array_memcpy(packet1.model_name, packet_in.model_name, sizeof(char)*32); - mav_array_memcpy(packet1.custom_name, packet_in.custom_name, sizeof(char)*32); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_gimbal_device_information_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_gimbal_device_information_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_gimbal_device_information_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.vendor_name , packet1.model_name , packet1.custom_name , packet1.firmware_version , packet1.hardware_version , packet1.uid , packet1.cap_flags , packet1.custom_cap_flags , packet1.roll_min , packet1.roll_max , packet1.pitch_min , packet1.pitch_max , packet1.yaw_min , packet1.yaw_max , packet1.gimbal_device_id ); - mavlink_msg_gimbal_device_information_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_gimbal_device_information_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.vendor_name , packet1.model_name , packet1.custom_name , packet1.firmware_version , packet1.hardware_version , packet1.uid , packet1.cap_flags , packet1.custom_cap_flags , packet1.roll_min , packet1.roll_max , packet1.pitch_min , packet1.pitch_max , packet1.yaw_min , packet1.yaw_max , packet1.gimbal_device_id ); - mavlink_msg_gimbal_device_information_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_ATTITUDE >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_gimbal_device_set_attitude_t packet_in = { - { 17.0, 18.0, 19.0, 20.0 },129.0,157.0,185.0,18691,223,34 - }; - mavlink_gimbal_device_set_attitude_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.angular_velocity_x = packet_in.angular_velocity_x; - packet1.angular_velocity_y = packet_in.angular_velocity_y; - packet1.angular_velocity_z = packet_in.angular_velocity_z; - packet1.flags = packet_in.flags; - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - - mav_array_memcpy(packet1.q, packet_in.q, sizeof(float)*4); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_ATTITUDE_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_ATTITUDE_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_gimbal_device_set_attitude_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_gimbal_device_set_attitude_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_gimbal_device_set_attitude_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.flags , packet1.q , packet1.angular_velocity_x , packet1.angular_velocity_y , packet1.angular_velocity_z ); - mavlink_msg_gimbal_device_set_attitude_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_gimbal_device_set_attitude_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.flags , packet1.q , packet1.angular_velocity_x , packet1.angular_velocity_y , packet1.angular_velocity_z ); - mavlink_msg_gimbal_device_set_attitude_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_GIMBAL_DEVICE_ATTITUDE_STATUS >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_gimbal_device_attitude_status_t packet_in = { - 963497464,{ 45.0, 46.0, 47.0, 48.0 },157.0,185.0,213.0,963499128,19107,247,58,297.0,325.0,149 - }; - mavlink_gimbal_device_attitude_status_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_boot_ms = packet_in.time_boot_ms; - packet1.angular_velocity_x = packet_in.angular_velocity_x; - packet1.angular_velocity_y = packet_in.angular_velocity_y; - packet1.angular_velocity_z = packet_in.angular_velocity_z; - packet1.failure_flags = packet_in.failure_flags; - packet1.flags = packet_in.flags; - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - packet1.delta_yaw = packet_in.delta_yaw; - packet1.delta_yaw_velocity = packet_in.delta_yaw_velocity; - packet1.gimbal_device_id = packet_in.gimbal_device_id; - - mav_array_memcpy(packet1.q, packet_in.q, sizeof(float)*4); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_GIMBAL_DEVICE_ATTITUDE_STATUS_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_GIMBAL_DEVICE_ATTITUDE_STATUS_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_gimbal_device_attitude_status_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_gimbal_device_attitude_status_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_gimbal_device_attitude_status_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.time_boot_ms , packet1.flags , packet1.q , packet1.angular_velocity_x , packet1.angular_velocity_y , packet1.angular_velocity_z , packet1.failure_flags , packet1.delta_yaw , packet1.delta_yaw_velocity , packet1.gimbal_device_id ); - mavlink_msg_gimbal_device_attitude_status_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_gimbal_device_attitude_status_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.time_boot_ms , packet1.flags , packet1.q , packet1.angular_velocity_x , packet1.angular_velocity_y , packet1.angular_velocity_z , packet1.failure_flags , packet1.delta_yaw , packet1.delta_yaw_velocity , packet1.gimbal_device_id ); - mavlink_msg_gimbal_device_attitude_status_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_autopilot_state_for_gimbal_device_t packet_in = { - 93372036854775807ULL,{ 73.0, 74.0, 75.0, 76.0 },963498712,213.0,241.0,269.0,963499544,325.0,19731,27,94,161,388.0 - }; - mavlink_autopilot_state_for_gimbal_device_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_boot_us = packet_in.time_boot_us; - packet1.q_estimated_delay_us = packet_in.q_estimated_delay_us; - packet1.vx = packet_in.vx; - packet1.vy = packet_in.vy; - packet1.vz = packet_in.vz; - packet1.v_estimated_delay_us = packet_in.v_estimated_delay_us; - packet1.feed_forward_angular_velocity_z = packet_in.feed_forward_angular_velocity_z; - packet1.estimator_status = packet_in.estimator_status; - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - packet1.landed_state = packet_in.landed_state; - packet1.angular_velocity_z = packet_in.angular_velocity_z; - - mav_array_memcpy(packet1.q, packet_in.q, sizeof(float)*4); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_autopilot_state_for_gimbal_device_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_autopilot_state_for_gimbal_device_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_autopilot_state_for_gimbal_device_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.time_boot_us , packet1.q , packet1.q_estimated_delay_us , packet1.vx , packet1.vy , packet1.vz , packet1.v_estimated_delay_us , packet1.feed_forward_angular_velocity_z , packet1.estimator_status , packet1.landed_state , packet1.angular_velocity_z ); - mavlink_msg_autopilot_state_for_gimbal_device_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_autopilot_state_for_gimbal_device_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.time_boot_us , packet1.q , packet1.q_estimated_delay_us , packet1.vx , packet1.vy , packet1.vz , packet1.v_estimated_delay_us , packet1.feed_forward_angular_velocity_z , packet1.estimator_status , packet1.landed_state , packet1.angular_velocity_z ); - mavlink_msg_autopilot_state_for_gimbal_device_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_PITCHYAW >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_gimbal_manager_set_pitchyaw_t packet_in = { - 963497464,45.0,73.0,101.0,129.0,65,132,199 - }; - mavlink_gimbal_manager_set_pitchyaw_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.flags = packet_in.flags; - packet1.pitch = packet_in.pitch; - packet1.yaw = packet_in.yaw; - packet1.pitch_rate = packet_in.pitch_rate; - packet1.yaw_rate = packet_in.yaw_rate; - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - packet1.gimbal_device_id = packet_in.gimbal_device_id; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_PITCHYAW_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_PITCHYAW_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_gimbal_manager_set_pitchyaw_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_gimbal_manager_set_pitchyaw_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_gimbal_manager_set_pitchyaw_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.flags , packet1.gimbal_device_id , packet1.pitch , packet1.yaw , packet1.pitch_rate , packet1.yaw_rate ); - mavlink_msg_gimbal_manager_set_pitchyaw_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_gimbal_manager_set_pitchyaw_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.flags , packet1.gimbal_device_id , packet1.pitch , packet1.yaw , packet1.pitch_rate , packet1.yaw_rate ); - mavlink_msg_gimbal_manager_set_pitchyaw_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_MANUAL_CONTROL >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_gimbal_manager_set_manual_control_t packet_in = { - 963497464,45.0,73.0,101.0,129.0,65,132,199 - }; - mavlink_gimbal_manager_set_manual_control_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.flags = packet_in.flags; - packet1.pitch = packet_in.pitch; - packet1.yaw = packet_in.yaw; - packet1.pitch_rate = packet_in.pitch_rate; - packet1.yaw_rate = packet_in.yaw_rate; - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - packet1.gimbal_device_id = packet_in.gimbal_device_id; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_MANUAL_CONTROL_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_MANUAL_CONTROL_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_gimbal_manager_set_manual_control_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_gimbal_manager_set_manual_control_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_gimbal_manager_set_manual_control_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.flags , packet1.gimbal_device_id , packet1.pitch , packet1.yaw , packet1.pitch_rate , packet1.yaw_rate ); - mavlink_msg_gimbal_manager_set_manual_control_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_gimbal_manager_set_manual_control_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.flags , packet1.gimbal_device_id , packet1.pitch , packet1.yaw , packet1.pitch_rate , packet1.yaw_rate ); - mavlink_msg_gimbal_manager_set_manual_control_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_ESC_INFO >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_esc_info_t packet_in = { - 93372036854775807ULL,{ 963497880, 963497881, 963497882, 963497883 },18483,{ 18587, 18588, 18589, 18590 },{ 19003, 19004, 19005, 19006 },3,70,137,204 - }; - mavlink_esc_info_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_usec = packet_in.time_usec; - packet1.counter = packet_in.counter; - packet1.index = packet_in.index; - packet1.count = packet_in.count; - packet1.connection_type = packet_in.connection_type; - packet1.info = packet_in.info; - - mav_array_memcpy(packet1.error_count, packet_in.error_count, sizeof(uint32_t)*4); - mav_array_memcpy(packet1.failure_flags, packet_in.failure_flags, sizeof(uint16_t)*4); - mav_array_memcpy(packet1.temperature, packet_in.temperature, sizeof(int16_t)*4); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_ESC_INFO_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_ESC_INFO_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_esc_info_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_esc_info_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_esc_info_pack(system_id, component_id, &msg , packet1.index , packet1.time_usec , packet1.counter , packet1.count , packet1.connection_type , packet1.info , packet1.failure_flags , packet1.error_count , packet1.temperature ); - mavlink_msg_esc_info_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_esc_info_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.index , packet1.time_usec , packet1.counter , packet1.count , packet1.connection_type , packet1.info , packet1.failure_flags , packet1.error_count , packet1.temperature ); - mavlink_msg_esc_info_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_ESC_STATUS >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_esc_status_t packet_in = { - 93372036854775807ULL,{ 963497880, 963497881, 963497882, 963497883 },{ 185.0, 186.0, 187.0, 188.0 },{ 297.0, 298.0, 299.0, 300.0 },173 - }; - mavlink_esc_status_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_usec = packet_in.time_usec; - packet1.index = packet_in.index; - - mav_array_memcpy(packet1.rpm, packet_in.rpm, sizeof(int32_t)*4); - mav_array_memcpy(packet1.voltage, packet_in.voltage, sizeof(float)*4); - mav_array_memcpy(packet1.current, packet_in.current, sizeof(float)*4); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_ESC_STATUS_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_ESC_STATUS_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_esc_status_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_esc_status_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_esc_status_pack(system_id, component_id, &msg , packet1.index , packet1.time_usec , packet1.rpm , packet1.voltage , packet1.current ); - mavlink_msg_esc_status_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_esc_status_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.index , packet1.time_usec , packet1.rpm , packet1.voltage , packet1.current ); - mavlink_msg_esc_status_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_WIFI_CONFIG_AP >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_wifi_config_ap_t packet_in = { - "ABCDEFGHIJKLMNOPQRSTUVWXYZABCDE","GHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQ",37,104 - }; - mavlink_wifi_config_ap_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.mode = packet_in.mode; - packet1.response = packet_in.response; - - mav_array_memcpy(packet1.ssid, packet_in.ssid, sizeof(char)*32); - mav_array_memcpy(packet1.password, packet_in.password, sizeof(char)*64); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_WIFI_CONFIG_AP_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_WIFI_CONFIG_AP_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_wifi_config_ap_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_wifi_config_ap_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_wifi_config_ap_pack(system_id, component_id, &msg , packet1.ssid , packet1.password , packet1.mode , packet1.response ); - mavlink_msg_wifi_config_ap_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_wifi_config_ap_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.ssid , packet1.password , packet1.mode , packet1.response ); - mavlink_msg_wifi_config_ap_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_AIS_VESSEL >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_ais_vessel_t packet_in = { - 963497464,963497672,963497880,17859,17963,18067,18171,18275,18379,18483,211,22,89,156,223,"FGHIJK","MNOPQRSTUVWXYZABCDE" - }; - mavlink_ais_vessel_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.MMSI = packet_in.MMSI; - packet1.lat = packet_in.lat; - packet1.lon = packet_in.lon; - packet1.COG = packet_in.COG; - packet1.heading = packet_in.heading; - packet1.velocity = packet_in.velocity; - packet1.dimension_bow = packet_in.dimension_bow; - packet1.dimension_stern = packet_in.dimension_stern; - packet1.tslc = packet_in.tslc; - packet1.flags = packet_in.flags; - packet1.turn_rate = packet_in.turn_rate; - packet1.navigational_status = packet_in.navigational_status; - packet1.type = packet_in.type; - packet1.dimension_port = packet_in.dimension_port; - packet1.dimension_starboard = packet_in.dimension_starboard; - - mav_array_memcpy(packet1.callsign, packet_in.callsign, sizeof(char)*7); - mav_array_memcpy(packet1.name, packet_in.name, sizeof(char)*20); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_AIS_VESSEL_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_AIS_VESSEL_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_ais_vessel_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_ais_vessel_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_ais_vessel_pack(system_id, component_id, &msg , packet1.MMSI , packet1.lat , packet1.lon , packet1.COG , packet1.heading , packet1.velocity , packet1.turn_rate , packet1.navigational_status , packet1.type , packet1.dimension_bow , packet1.dimension_stern , packet1.dimension_port , packet1.dimension_starboard , packet1.callsign , packet1.name , packet1.tslc , packet1.flags ); - mavlink_msg_ais_vessel_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_ais_vessel_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.MMSI , packet1.lat , packet1.lon , packet1.COG , packet1.heading , packet1.velocity , packet1.turn_rate , packet1.navigational_status , packet1.type , packet1.dimension_bow , packet1.dimension_stern , packet1.dimension_port , packet1.dimension_starboard , packet1.callsign , packet1.name , packet1.tslc , packet1.flags ); - mavlink_msg_ais_vessel_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_UAVCAN_NODE_STATUS >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_uavcan_node_status_t packet_in = { - 93372036854775807ULL,963497880,17859,175,242,53 - }; - mavlink_uavcan_node_status_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_usec = packet_in.time_usec; - packet1.uptime_sec = packet_in.uptime_sec; - packet1.vendor_specific_status_code = packet_in.vendor_specific_status_code; - packet1.health = packet_in.health; - packet1.mode = packet_in.mode; - packet1.sub_mode = packet_in.sub_mode; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_UAVCAN_NODE_STATUS_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_UAVCAN_NODE_STATUS_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_uavcan_node_status_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_uavcan_node_status_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_uavcan_node_status_pack(system_id, component_id, &msg , packet1.time_usec , packet1.uptime_sec , packet1.health , packet1.mode , packet1.sub_mode , packet1.vendor_specific_status_code ); - mavlink_msg_uavcan_node_status_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_uavcan_node_status_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.uptime_sec , packet1.health , packet1.mode , packet1.sub_mode , packet1.vendor_specific_status_code ); - mavlink_msg_uavcan_node_status_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_UAVCAN_NODE_INFO >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_uavcan_node_info_t packet_in = { - 93372036854775807ULL,963497880,963498088,"QRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQ",37,104,{ 171, 172, 173, 174, 175, 176, 177, 178, 179, 180, 181, 182, 183, 184, 185, 186 },219,30 - }; - mavlink_uavcan_node_info_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_usec = packet_in.time_usec; - packet1.uptime_sec = packet_in.uptime_sec; - packet1.sw_vcs_commit = packet_in.sw_vcs_commit; - packet1.hw_version_major = packet_in.hw_version_major; - packet1.hw_version_minor = packet_in.hw_version_minor; - packet1.sw_version_major = packet_in.sw_version_major; - packet1.sw_version_minor = packet_in.sw_version_minor; - - mav_array_memcpy(packet1.name, packet_in.name, sizeof(char)*80); - mav_array_memcpy(packet1.hw_unique_id, packet_in.hw_unique_id, sizeof(uint8_t)*16); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_UAVCAN_NODE_INFO_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_UAVCAN_NODE_INFO_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_uavcan_node_info_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_uavcan_node_info_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_uavcan_node_info_pack(system_id, component_id, &msg , packet1.time_usec , packet1.uptime_sec , packet1.name , packet1.hw_version_major , packet1.hw_version_minor , packet1.hw_unique_id , packet1.sw_version_major , packet1.sw_version_minor , packet1.sw_vcs_commit ); - mavlink_msg_uavcan_node_info_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_uavcan_node_info_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.uptime_sec , packet1.name , packet1.hw_version_major , packet1.hw_version_minor , packet1.hw_unique_id , packet1.sw_version_major , packet1.sw_version_minor , packet1.sw_vcs_commit ); - mavlink_msg_uavcan_node_info_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_PARAM_EXT_REQUEST_READ >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_param_ext_request_read_t packet_in = { - 17235,139,206,"EFGHIJKLMNOPQRS" - }; - mavlink_param_ext_request_read_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.param_index = packet_in.param_index; - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - - mav_array_memcpy(packet1.param_id, packet_in.param_id, sizeof(char)*16); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_PARAM_EXT_REQUEST_READ_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_PARAM_EXT_REQUEST_READ_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_param_ext_request_read_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_param_ext_request_read_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_param_ext_request_read_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.param_id , packet1.param_index ); - mavlink_msg_param_ext_request_read_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_param_ext_request_read_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.param_id , packet1.param_index ); - mavlink_msg_param_ext_request_read_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_PARAM_EXT_REQUEST_LIST >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_param_ext_request_list_t packet_in = { - 5,72 - }; - mavlink_param_ext_request_list_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_PARAM_EXT_REQUEST_LIST_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_PARAM_EXT_REQUEST_LIST_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_param_ext_request_list_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_param_ext_request_list_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_param_ext_request_list_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component ); - mavlink_msg_param_ext_request_list_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_param_ext_request_list_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component ); - mavlink_msg_param_ext_request_list_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_PARAM_EXT_VALUE >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_param_ext_value_t packet_in = { - 17235,17339,"EFGHIJKLMNOPQRS","UVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQ",193 - }; - mavlink_param_ext_value_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.param_count = packet_in.param_count; - packet1.param_index = packet_in.param_index; - packet1.param_type = packet_in.param_type; - - mav_array_memcpy(packet1.param_id, packet_in.param_id, sizeof(char)*16); - mav_array_memcpy(packet1.param_value, packet_in.param_value, sizeof(char)*128); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_PARAM_EXT_VALUE_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_PARAM_EXT_VALUE_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_param_ext_value_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_param_ext_value_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_param_ext_value_pack(system_id, component_id, &msg , packet1.param_id , packet1.param_value , packet1.param_type , packet1.param_count , packet1.param_index ); - mavlink_msg_param_ext_value_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_param_ext_value_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.param_id , packet1.param_value , packet1.param_type , packet1.param_count , packet1.param_index ); - mavlink_msg_param_ext_value_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_PARAM_EXT_SET >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_param_ext_set_t packet_in = { - 5,72,"CDEFGHIJKLMNOPQ","STUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNO",59 - }; - mavlink_param_ext_set_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - packet1.param_type = packet_in.param_type; - - mav_array_memcpy(packet1.param_id, packet_in.param_id, sizeof(char)*16); - mav_array_memcpy(packet1.param_value, packet_in.param_value, sizeof(char)*128); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_PARAM_EXT_SET_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_PARAM_EXT_SET_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_param_ext_set_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_param_ext_set_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_param_ext_set_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.param_id , packet1.param_value , packet1.param_type ); - mavlink_msg_param_ext_set_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_param_ext_set_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.param_id , packet1.param_value , packet1.param_type ); - mavlink_msg_param_ext_set_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_PARAM_EXT_ACK >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_param_ext_ack_t packet_in = { - "ABCDEFGHIJKLMNO","QRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLM",181,248 - }; - mavlink_param_ext_ack_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.param_type = packet_in.param_type; - packet1.param_result = packet_in.param_result; - - mav_array_memcpy(packet1.param_id, packet_in.param_id, sizeof(char)*16); - mav_array_memcpy(packet1.param_value, packet_in.param_value, sizeof(char)*128); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_PARAM_EXT_ACK_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_PARAM_EXT_ACK_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_param_ext_ack_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_param_ext_ack_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_param_ext_ack_pack(system_id, component_id, &msg , packet1.param_id , packet1.param_value , packet1.param_type , packet1.param_result ); - mavlink_msg_param_ext_ack_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_param_ext_ack_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.param_id , packet1.param_value , packet1.param_type , packet1.param_result ); - mavlink_msg_param_ext_ack_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_OBSTACLE_DISTANCE >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_obstacle_distance_t packet_in = { - 93372036854775807ULL,{ 17651, 17652, 17653, 17654, 17655, 17656, 17657, 17658, 17659, 17660, 17661, 17662, 17663, 17664, 17665, 17666, 17667, 17668, 17669, 17670, 17671, 17672, 17673, 17674, 17675, 17676, 17677, 17678, 17679, 17680, 17681, 17682, 17683, 17684, 17685, 17686, 17687, 17688, 17689, 17690, 17691, 17692, 17693, 17694, 17695, 17696, 17697, 17698, 17699, 17700, 17701, 17702, 17703, 17704, 17705, 17706, 17707, 17708, 17709, 17710, 17711, 17712, 17713, 17714, 17715, 17716, 17717, 17718, 17719, 17720, 17721, 17722 },25139,25243,217,28,1123.0,1151.0,119 - }; - mavlink_obstacle_distance_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_usec = packet_in.time_usec; - packet1.min_distance = packet_in.min_distance; - packet1.max_distance = packet_in.max_distance; - packet1.sensor_type = packet_in.sensor_type; - packet1.increment = packet_in.increment; - packet1.increment_f = packet_in.increment_f; - packet1.angle_offset = packet_in.angle_offset; - packet1.frame = packet_in.frame; - - mav_array_memcpy(packet1.distances, packet_in.distances, sizeof(uint16_t)*72); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_OBSTACLE_DISTANCE_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_OBSTACLE_DISTANCE_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_obstacle_distance_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_obstacle_distance_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_obstacle_distance_pack(system_id, component_id, &msg , packet1.time_usec , packet1.sensor_type , packet1.distances , packet1.increment , packet1.min_distance , packet1.max_distance , packet1.increment_f , packet1.angle_offset , packet1.frame ); - mavlink_msg_obstacle_distance_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_obstacle_distance_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.sensor_type , packet1.distances , packet1.increment , packet1.min_distance , packet1.max_distance , packet1.increment_f , packet1.angle_offset , packet1.frame ); - mavlink_msg_obstacle_distance_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_ODOMETRY >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_odometry_t packet_in = { - 93372036854775807ULL,73.0,101.0,129.0,{ 157.0, 158.0, 159.0, 160.0 },269.0,297.0,325.0,353.0,381.0,409.0,{ 437.0, 438.0, 439.0, 440.0, 441.0, 442.0, 443.0, 444.0, 445.0, 446.0, 447.0, 448.0, 449.0, 450.0, 451.0, 452.0, 453.0, 454.0, 455.0, 456.0, 457.0 },{ 1025.0, 1026.0, 1027.0, 1028.0, 1029.0, 1030.0, 1031.0, 1032.0, 1033.0, 1034.0, 1035.0, 1036.0, 1037.0, 1038.0, 1039.0, 1040.0, 1041.0, 1042.0, 1043.0, 1044.0, 1045.0 },177,244,55,122,189 - }; - mavlink_odometry_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_usec = packet_in.time_usec; - packet1.x = packet_in.x; - packet1.y = packet_in.y; - packet1.z = packet_in.z; - packet1.vx = packet_in.vx; - packet1.vy = packet_in.vy; - packet1.vz = packet_in.vz; - packet1.rollspeed = packet_in.rollspeed; - packet1.pitchspeed = packet_in.pitchspeed; - packet1.yawspeed = packet_in.yawspeed; - packet1.frame_id = packet_in.frame_id; - packet1.child_frame_id = packet_in.child_frame_id; - packet1.reset_counter = packet_in.reset_counter; - packet1.estimator_type = packet_in.estimator_type; - packet1.quality = packet_in.quality; - - mav_array_memcpy(packet1.q, packet_in.q, sizeof(float)*4); - mav_array_memcpy(packet1.pose_covariance, packet_in.pose_covariance, sizeof(float)*21); - mav_array_memcpy(packet1.velocity_covariance, packet_in.velocity_covariance, sizeof(float)*21); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_ODOMETRY_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_ODOMETRY_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_odometry_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_odometry_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_odometry_pack(system_id, component_id, &msg , packet1.time_usec , packet1.frame_id , packet1.child_frame_id , packet1.x , packet1.y , packet1.z , packet1.q , packet1.vx , packet1.vy , packet1.vz , packet1.rollspeed , packet1.pitchspeed , packet1.yawspeed , packet1.pose_covariance , packet1.velocity_covariance , packet1.reset_counter , packet1.estimator_type , packet1.quality ); - mavlink_msg_odometry_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_odometry_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.frame_id , packet1.child_frame_id , packet1.x , packet1.y , packet1.z , packet1.q , packet1.vx , packet1.vy , packet1.vz , packet1.rollspeed , packet1.pitchspeed , packet1.yawspeed , packet1.pose_covariance , packet1.velocity_covariance , packet1.reset_counter , packet1.estimator_type , packet1.quality ); - mavlink_msg_odometry_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_TRAJECTORY_REPRESENTATION_WAYPOINTS >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_trajectory_representation_waypoints_t packet_in = { - 93372036854775807ULL,{ 73.0, 74.0, 75.0, 76.0, 77.0 },{ 213.0, 214.0, 215.0, 216.0, 217.0 },{ 353.0, 354.0, 355.0, 356.0, 357.0 },{ 493.0, 494.0, 495.0, 496.0, 497.0 },{ 633.0, 634.0, 635.0, 636.0, 637.0 },{ 773.0, 774.0, 775.0, 776.0, 777.0 },{ 913.0, 914.0, 915.0, 916.0, 917.0 },{ 1053.0, 1054.0, 1055.0, 1056.0, 1057.0 },{ 1193.0, 1194.0, 1195.0, 1196.0, 1197.0 },{ 1333.0, 1334.0, 1335.0, 1336.0, 1337.0 },{ 1473.0, 1474.0, 1475.0, 1476.0, 1477.0 },{ 29091, 29092, 29093, 29094, 29095 },79 - }; - mavlink_trajectory_representation_waypoints_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_usec = packet_in.time_usec; - packet1.valid_points = packet_in.valid_points; - - mav_array_memcpy(packet1.pos_x, packet_in.pos_x, sizeof(float)*5); - mav_array_memcpy(packet1.pos_y, packet_in.pos_y, sizeof(float)*5); - mav_array_memcpy(packet1.pos_z, packet_in.pos_z, sizeof(float)*5); - mav_array_memcpy(packet1.vel_x, packet_in.vel_x, sizeof(float)*5); - mav_array_memcpy(packet1.vel_y, packet_in.vel_y, sizeof(float)*5); - mav_array_memcpy(packet1.vel_z, packet_in.vel_z, sizeof(float)*5); - mav_array_memcpy(packet1.acc_x, packet_in.acc_x, sizeof(float)*5); - mav_array_memcpy(packet1.acc_y, packet_in.acc_y, sizeof(float)*5); - mav_array_memcpy(packet1.acc_z, packet_in.acc_z, sizeof(float)*5); - mav_array_memcpy(packet1.pos_yaw, packet_in.pos_yaw, sizeof(float)*5); - mav_array_memcpy(packet1.vel_yaw, packet_in.vel_yaw, sizeof(float)*5); - mav_array_memcpy(packet1.command, packet_in.command, sizeof(uint16_t)*5); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_TRAJECTORY_REPRESENTATION_WAYPOINTS_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_TRAJECTORY_REPRESENTATION_WAYPOINTS_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_trajectory_representation_waypoints_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_trajectory_representation_waypoints_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_trajectory_representation_waypoints_pack(system_id, component_id, &msg , packet1.time_usec , packet1.valid_points , packet1.pos_x , packet1.pos_y , packet1.pos_z , packet1.vel_x , packet1.vel_y , packet1.vel_z , packet1.acc_x , packet1.acc_y , packet1.acc_z , packet1.pos_yaw , packet1.vel_yaw , packet1.command ); - mavlink_msg_trajectory_representation_waypoints_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_trajectory_representation_waypoints_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.valid_points , packet1.pos_x , packet1.pos_y , packet1.pos_z , packet1.vel_x , packet1.vel_y , packet1.vel_z , packet1.acc_x , packet1.acc_y , packet1.acc_z , packet1.pos_yaw , packet1.vel_yaw , packet1.command ); - mavlink_msg_trajectory_representation_waypoints_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_TRAJECTORY_REPRESENTATION_BEZIER >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_trajectory_representation_bezier_t packet_in = { - 93372036854775807ULL,{ 73.0, 74.0, 75.0, 76.0, 77.0 },{ 213.0, 214.0, 215.0, 216.0, 217.0 },{ 353.0, 354.0, 355.0, 356.0, 357.0 },{ 493.0, 494.0, 495.0, 496.0, 497.0 },{ 633.0, 634.0, 635.0, 636.0, 637.0 },73 - }; - mavlink_trajectory_representation_bezier_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_usec = packet_in.time_usec; - packet1.valid_points = packet_in.valid_points; - - mav_array_memcpy(packet1.pos_x, packet_in.pos_x, sizeof(float)*5); - mav_array_memcpy(packet1.pos_y, packet_in.pos_y, sizeof(float)*5); - mav_array_memcpy(packet1.pos_z, packet_in.pos_z, sizeof(float)*5); - mav_array_memcpy(packet1.delta, packet_in.delta, sizeof(float)*5); - mav_array_memcpy(packet1.pos_yaw, packet_in.pos_yaw, sizeof(float)*5); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_TRAJECTORY_REPRESENTATION_BEZIER_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_TRAJECTORY_REPRESENTATION_BEZIER_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_trajectory_representation_bezier_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_trajectory_representation_bezier_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_trajectory_representation_bezier_pack(system_id, component_id, &msg , packet1.time_usec , packet1.valid_points , packet1.pos_x , packet1.pos_y , packet1.pos_z , packet1.delta , packet1.pos_yaw ); - mavlink_msg_trajectory_representation_bezier_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_trajectory_representation_bezier_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.valid_points , packet1.pos_x , packet1.pos_y , packet1.pos_z , packet1.delta , packet1.pos_yaw ); - mavlink_msg_trajectory_representation_bezier_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_CELLULAR_STATUS >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_cellular_status_t packet_in = { - 17235,17339,17443,151,218,29,96 - }; - mavlink_cellular_status_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.mcc = packet_in.mcc; - packet1.mnc = packet_in.mnc; - packet1.lac = packet_in.lac; - packet1.status = packet_in.status; - packet1.failure_reason = packet_in.failure_reason; - packet1.type = packet_in.type; - packet1.quality = packet_in.quality; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_CELLULAR_STATUS_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_CELLULAR_STATUS_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_cellular_status_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_cellular_status_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_cellular_status_pack(system_id, component_id, &msg , packet1.status , packet1.failure_reason , packet1.type , packet1.quality , packet1.mcc , packet1.mnc , packet1.lac ); - mavlink_msg_cellular_status_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_cellular_status_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.status , packet1.failure_reason , packet1.type , packet1.quality , packet1.mcc , packet1.mnc , packet1.lac ); - mavlink_msg_cellular_status_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_ISBD_LINK_STATUS >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_isbd_link_status_t packet_in = { - 93372036854775807ULL,93372036854776311ULL,18067,18171,65,132,199,10 - }; - mavlink_isbd_link_status_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.timestamp = packet_in.timestamp; - packet1.last_heartbeat = packet_in.last_heartbeat; - packet1.failed_sessions = packet_in.failed_sessions; - packet1.successful_sessions = packet_in.successful_sessions; - packet1.signal_quality = packet_in.signal_quality; - packet1.ring_pending = packet_in.ring_pending; - packet1.tx_session_pending = packet_in.tx_session_pending; - packet1.rx_session_pending = packet_in.rx_session_pending; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_ISBD_LINK_STATUS_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_ISBD_LINK_STATUS_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_isbd_link_status_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_isbd_link_status_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_isbd_link_status_pack(system_id, component_id, &msg , packet1.timestamp , packet1.last_heartbeat , packet1.failed_sessions , packet1.successful_sessions , packet1.signal_quality , packet1.ring_pending , packet1.tx_session_pending , packet1.rx_session_pending ); - mavlink_msg_isbd_link_status_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_isbd_link_status_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.last_heartbeat , packet1.failed_sessions , packet1.successful_sessions , packet1.signal_quality , packet1.ring_pending , packet1.tx_session_pending , packet1.rx_session_pending ); - mavlink_msg_isbd_link_status_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_CELLULAR_CONFIG >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_cellular_config_t packet_in = { - 5,72,"CDEFGHIJKLMNOPQ","STUVWXYZABCDEFG","IJKLMNOPQRSTUVWXYZABCDEFGHIJKLM","OPQRSTUVWXYZABC",123,190 - }; - mavlink_cellular_config_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.enable_lte = packet_in.enable_lte; - packet1.enable_pin = packet_in.enable_pin; - packet1.roaming = packet_in.roaming; - packet1.response = packet_in.response; - - mav_array_memcpy(packet1.pin, packet_in.pin, sizeof(char)*16); - mav_array_memcpy(packet1.new_pin, packet_in.new_pin, sizeof(char)*16); - mav_array_memcpy(packet1.apn, packet_in.apn, sizeof(char)*32); - mav_array_memcpy(packet1.puk, packet_in.puk, sizeof(char)*16); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_CELLULAR_CONFIG_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_CELLULAR_CONFIG_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_cellular_config_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_cellular_config_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_cellular_config_pack(system_id, component_id, &msg , packet1.enable_lte , packet1.enable_pin , packet1.pin , packet1.new_pin , packet1.apn , packet1.puk , packet1.roaming , packet1.response ); - mavlink_msg_cellular_config_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_cellular_config_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.enable_lte , packet1.enable_pin , packet1.pin , packet1.new_pin , packet1.apn , packet1.puk , packet1.roaming , packet1.response ); - mavlink_msg_cellular_config_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_RAW_RPM >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_raw_rpm_t packet_in = { - 17.0,17 - }; - mavlink_raw_rpm_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.frequency = packet_in.frequency; - packet1.index = packet_in.index; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_RAW_RPM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_RAW_RPM_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_raw_rpm_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_raw_rpm_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_raw_rpm_pack(system_id, component_id, &msg , packet1.index , packet1.frequency ); - mavlink_msg_raw_rpm_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_raw_rpm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.index , packet1.frequency ); - mavlink_msg_raw_rpm_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_UTM_GLOBAL_POSITION >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_utm_global_position_t packet_in = { - 93372036854775807ULL,963497880,963498088,963498296,963498504,963498712,963498920,963499128,19107,19211,19315,19419,19523,19627,19731,{ 27, 28, 29, 30, 31, 32, 33, 34, 35, 36, 37, 38, 39, 40, 41, 42, 43, 44 },209,20 - }; - mavlink_utm_global_position_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time = packet_in.time; - packet1.lat = packet_in.lat; - packet1.lon = packet_in.lon; - packet1.alt = packet_in.alt; - packet1.relative_alt = packet_in.relative_alt; - packet1.next_lat = packet_in.next_lat; - packet1.next_lon = packet_in.next_lon; - packet1.next_alt = packet_in.next_alt; - packet1.vx = packet_in.vx; - packet1.vy = packet_in.vy; - packet1.vz = packet_in.vz; - packet1.h_acc = packet_in.h_acc; - packet1.v_acc = packet_in.v_acc; - packet1.vel_acc = packet_in.vel_acc; - packet1.update_rate = packet_in.update_rate; - packet1.flight_state = packet_in.flight_state; - packet1.flags = packet_in.flags; - - mav_array_memcpy(packet1.uas_id, packet_in.uas_id, sizeof(uint8_t)*18); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_UTM_GLOBAL_POSITION_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_UTM_GLOBAL_POSITION_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_utm_global_position_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_utm_global_position_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_utm_global_position_pack(system_id, component_id, &msg , packet1.time , packet1.uas_id , packet1.lat , packet1.lon , packet1.alt , packet1.relative_alt , packet1.vx , packet1.vy , packet1.vz , packet1.h_acc , packet1.v_acc , packet1.vel_acc , packet1.next_lat , packet1.next_lon , packet1.next_alt , packet1.update_rate , packet1.flight_state , packet1.flags ); - mavlink_msg_utm_global_position_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_utm_global_position_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time , packet1.uas_id , packet1.lat , packet1.lon , packet1.alt , packet1.relative_alt , packet1.vx , packet1.vy , packet1.vz , packet1.h_acc , packet1.v_acc , packet1.vel_acc , packet1.next_lat , packet1.next_lon , packet1.next_alt , packet1.update_rate , packet1.flight_state , packet1.flags ); - mavlink_msg_utm_global_position_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_DEBUG_FLOAT_ARRAY >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_debug_float_array_t packet_in = { - 93372036854775807ULL,17651,"KLMNOPQRS",{ 157.0, 158.0, 159.0, 160.0, 161.0, 162.0, 163.0, 164.0, 165.0, 166.0, 167.0, 168.0, 169.0, 170.0, 171.0, 172.0, 173.0, 174.0, 175.0, 176.0, 177.0, 178.0, 179.0, 180.0, 181.0, 182.0, 183.0, 184.0, 185.0, 186.0, 187.0, 188.0, 189.0, 190.0, 191.0, 192.0, 193.0, 194.0, 195.0, 196.0, 197.0, 198.0, 199.0, 200.0, 201.0, 202.0, 203.0, 204.0, 205.0, 206.0, 207.0, 208.0, 209.0, 210.0, 211.0, 212.0, 213.0, 214.0 } - }; - mavlink_debug_float_array_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_usec = packet_in.time_usec; - packet1.array_id = packet_in.array_id; - - mav_array_memcpy(packet1.name, packet_in.name, sizeof(char)*10); - mav_array_memcpy(packet1.data, packet_in.data, sizeof(float)*58); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_DEBUG_FLOAT_ARRAY_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_DEBUG_FLOAT_ARRAY_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_debug_float_array_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_debug_float_array_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_debug_float_array_pack(system_id, component_id, &msg , packet1.time_usec , packet1.name , packet1.array_id , packet1.data ); - mavlink_msg_debug_float_array_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_debug_float_array_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.name , packet1.array_id , packet1.data ); - mavlink_msg_debug_float_array_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_orbit_execution_status_t packet_in = { - 93372036854775807ULL,73.0,963498088,963498296,157.0,77 - }; - mavlink_orbit_execution_status_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_usec = packet_in.time_usec; - packet1.radius = packet_in.radius; - packet1.x = packet_in.x; - packet1.y = packet_in.y; - packet1.z = packet_in.z; - packet1.frame = packet_in.frame; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_orbit_execution_status_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_orbit_execution_status_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_orbit_execution_status_pack(system_id, component_id, &msg , packet1.time_usec , packet1.radius , packet1.frame , packet1.x , packet1.y , packet1.z ); - mavlink_msg_orbit_execution_status_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_orbit_execution_status_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.radius , packet1.frame , packet1.x , packet1.y , packet1.z ); - mavlink_msg_orbit_execution_status_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_SMART_BATTERY_INFO >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_smart_battery_info_t packet_in = { - 963497464,963497672,17651,17755,17859,17963,18067,187,254,65,"VWXYZABCDEFGHIJ","LMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGH",21759,80,963502144,963502352,"UVWXYZABCD" - }; - mavlink_smart_battery_info_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.capacity_full_specification = packet_in.capacity_full_specification; - packet1.capacity_full = packet_in.capacity_full; - packet1.cycle_count = packet_in.cycle_count; - packet1.weight = packet_in.weight; - packet1.discharge_minimum_voltage = packet_in.discharge_minimum_voltage; - packet1.charging_minimum_voltage = packet_in.charging_minimum_voltage; - packet1.resting_minimum_voltage = packet_in.resting_minimum_voltage; - packet1.id = packet_in.id; - packet1.battery_function = packet_in.battery_function; - packet1.type = packet_in.type; - packet1.charging_maximum_voltage = packet_in.charging_maximum_voltage; - packet1.cells_in_series = packet_in.cells_in_series; - packet1.discharge_maximum_current = packet_in.discharge_maximum_current; - packet1.discharge_maximum_burst_current = packet_in.discharge_maximum_burst_current; - - mav_array_memcpy(packet1.serial_number, packet_in.serial_number, sizeof(char)*16); - mav_array_memcpy(packet1.device_name, packet_in.device_name, sizeof(char)*50); - mav_array_memcpy(packet1.manufacture_date, packet_in.manufacture_date, sizeof(char)*11); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_SMART_BATTERY_INFO_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SMART_BATTERY_INFO_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_smart_battery_info_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_smart_battery_info_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_smart_battery_info_pack(system_id, component_id, &msg , packet1.id , packet1.battery_function , packet1.type , packet1.capacity_full_specification , packet1.capacity_full , packet1.cycle_count , packet1.serial_number , packet1.device_name , packet1.weight , packet1.discharge_minimum_voltage , packet1.charging_minimum_voltage , packet1.resting_minimum_voltage , packet1.charging_maximum_voltage , packet1.cells_in_series , packet1.discharge_maximum_current , packet1.discharge_maximum_burst_current , packet1.manufacture_date ); - mavlink_msg_smart_battery_info_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_smart_battery_info_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.id , packet1.battery_function , packet1.type , packet1.capacity_full_specification , packet1.capacity_full , packet1.cycle_count , packet1.serial_number , packet1.device_name , packet1.weight , packet1.discharge_minimum_voltage , packet1.charging_minimum_voltage , packet1.resting_minimum_voltage , packet1.charging_maximum_voltage , packet1.cells_in_series , packet1.discharge_maximum_current , packet1.discharge_maximum_burst_current , packet1.manufacture_date ); - mavlink_msg_smart_battery_info_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_GENERATOR_STATUS >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_generator_status_t packet_in = { - 93372036854775807ULL,73.0,101.0,129.0,157.0,185.0,963498920,963499128,19107,19211,19315 - }; - mavlink_generator_status_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.status = packet_in.status; - packet1.battery_current = packet_in.battery_current; - packet1.load_current = packet_in.load_current; - packet1.power_generated = packet_in.power_generated; - packet1.bus_voltage = packet_in.bus_voltage; - packet1.bat_current_setpoint = packet_in.bat_current_setpoint; - packet1.runtime = packet_in.runtime; - packet1.time_until_maintenance = packet_in.time_until_maintenance; - packet1.generator_speed = packet_in.generator_speed; - packet1.rectifier_temperature = packet_in.rectifier_temperature; - packet1.generator_temperature = packet_in.generator_temperature; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_GENERATOR_STATUS_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_GENERATOR_STATUS_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_generator_status_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_generator_status_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_generator_status_pack(system_id, component_id, &msg , packet1.status , packet1.generator_speed , packet1.battery_current , packet1.load_current , packet1.power_generated , packet1.bus_voltage , packet1.rectifier_temperature , packet1.bat_current_setpoint , packet1.generator_temperature , packet1.runtime , packet1.time_until_maintenance ); - mavlink_msg_generator_status_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_generator_status_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.status , packet1.generator_speed , packet1.battery_current , packet1.load_current , packet1.power_generated , packet1.bus_voltage , packet1.rectifier_temperature , packet1.bat_current_setpoint , packet1.generator_temperature , packet1.runtime , packet1.time_until_maintenance ); - mavlink_msg_generator_status_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_ACTUATOR_OUTPUT_STATUS >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_actuator_output_status_t packet_in = { - 93372036854775807ULL,963497880,{ 101.0, 102.0, 103.0, 104.0, 105.0, 106.0, 107.0, 108.0, 109.0, 110.0, 111.0, 112.0, 113.0, 114.0, 115.0, 116.0, 117.0, 118.0, 119.0, 120.0, 121.0, 122.0, 123.0, 124.0, 125.0, 126.0, 127.0, 128.0, 129.0, 130.0, 131.0, 132.0 } - }; - mavlink_actuator_output_status_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_usec = packet_in.time_usec; - packet1.active = packet_in.active; - - mav_array_memcpy(packet1.actuator, packet_in.actuator, sizeof(float)*32); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_ACTUATOR_OUTPUT_STATUS_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_ACTUATOR_OUTPUT_STATUS_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_actuator_output_status_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_actuator_output_status_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_actuator_output_status_pack(system_id, component_id, &msg , packet1.time_usec , packet1.active , packet1.actuator ); - mavlink_msg_actuator_output_status_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_actuator_output_status_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.active , packet1.actuator ); - mavlink_msg_actuator_output_status_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_TIME_ESTIMATE_TO_TARGET >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_time_estimate_to_target_t packet_in = { - 963497464,963497672,963497880,963498088,963498296 - }; - mavlink_time_estimate_to_target_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.safe_return = packet_in.safe_return; - packet1.land = packet_in.land; - packet1.mission_next_item = packet_in.mission_next_item; - packet1.mission_end = packet_in.mission_end; - packet1.commanded_action = packet_in.commanded_action; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_TIME_ESTIMATE_TO_TARGET_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_TIME_ESTIMATE_TO_TARGET_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_time_estimate_to_target_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_time_estimate_to_target_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_time_estimate_to_target_pack(system_id, component_id, &msg , packet1.safe_return , packet1.land , packet1.mission_next_item , packet1.mission_end , packet1.commanded_action ); - mavlink_msg_time_estimate_to_target_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_time_estimate_to_target_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.safe_return , packet1.land , packet1.mission_next_item , packet1.mission_end , packet1.commanded_action ); - mavlink_msg_time_estimate_to_target_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_TUNNEL >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_tunnel_t packet_in = { - 17235,139,206,17,{ 84, 85, 86, 87, 88, 89, 90, 91, 92, 93, 94, 95, 96, 97, 98, 99, 100, 101, 102, 103, 104, 105, 106, 107, 108, 109, 110, 111, 112, 113, 114, 115, 116, 117, 118, 119, 120, 121, 122, 123, 124, 125, 126, 127, 128, 129, 130, 131, 132, 133, 134, 135, 136, 137, 138, 139, 140, 141, 142, 143, 144, 145, 146, 147, 148, 149, 150, 151, 152, 153, 154, 155, 156, 157, 158, 159, 160, 161, 162, 163, 164, 165, 166, 167, 168, 169, 170, 171, 172, 173, 174, 175, 176, 177, 178, 179, 180, 181, 182, 183, 184, 185, 186, 187, 188, 189, 190, 191, 192, 193, 194, 195, 196, 197, 198, 199, 200, 201, 202, 203, 204, 205, 206, 207, 208, 209, 210, 211 } - }; - mavlink_tunnel_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.payload_type = packet_in.payload_type; - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - packet1.payload_length = packet_in.payload_length; - - mav_array_memcpy(packet1.payload, packet_in.payload, sizeof(uint8_t)*128); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_TUNNEL_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_TUNNEL_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_tunnel_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_tunnel_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_tunnel_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.payload_type , packet1.payload_length , packet1.payload ); - mavlink_msg_tunnel_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_tunnel_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.payload_type , packet1.payload_length , packet1.payload ); - mavlink_msg_tunnel_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_CAN_FRAME >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_can_frame_t packet_in = { - 963497464,17,84,151,218,{ 29, 30, 31, 32, 33, 34, 35, 36 } - }; - mavlink_can_frame_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.id = packet_in.id; - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - packet1.bus = packet_in.bus; - packet1.len = packet_in.len; - - mav_array_memcpy(packet1.data, packet_in.data, sizeof(uint8_t)*8); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_CAN_FRAME_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_CAN_FRAME_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_can_frame_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_can_frame_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_can_frame_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.bus , packet1.len , packet1.id , packet1.data ); - mavlink_msg_can_frame_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_can_frame_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.bus , packet1.len , packet1.id , packet1.data ); - mavlink_msg_can_frame_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_ONBOARD_COMPUTER_STATUS >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_onboard_computer_status_t packet_in = { - 93372036854775807ULL,963497880,963498088,963498296,{ 963498504, 963498505, 963498506, 963498507 },{ 963499336, 963499337, 963499338, 963499339 },{ 963500168, 963500169, 963500170, 963500171 },{ 963501000, 963501001, 963501002, 963501003, 963501004, 963501005 },{ 963502248, 963502249, 963502250, 963502251, 963502252, 963502253 },{ 963503496, 963503497, 963503498, 963503499, 963503500, 963503501 },{ 963504744, 963504745, 963504746, 963504747, 963504748, 963504749 },{ 963505992, 963505993, 963505994, 963505995, 963505996, 963505997 },{ 27011, 27012, 27013, 27014 },81,{ 148, 149, 150, 151, 152, 153, 154, 155 },{ 172, 173, 174, 175, 176, 177, 178, 179, 180, 181 },{ 74, 75, 76, 77 },{ 86, 87, 88, 89, 90, 91, 92, 93, 94, 95 },244,{ 55, 56, 57, 58, 59, 60, 61, 62 } - }; - mavlink_onboard_computer_status_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_usec = packet_in.time_usec; - packet1.uptime = packet_in.uptime; - packet1.ram_usage = packet_in.ram_usage; - packet1.ram_total = packet_in.ram_total; - packet1.type = packet_in.type; - packet1.temperature_board = packet_in.temperature_board; - - mav_array_memcpy(packet1.storage_type, packet_in.storage_type, sizeof(uint32_t)*4); - mav_array_memcpy(packet1.storage_usage, packet_in.storage_usage, sizeof(uint32_t)*4); - mav_array_memcpy(packet1.storage_total, packet_in.storage_total, sizeof(uint32_t)*4); - mav_array_memcpy(packet1.link_type, packet_in.link_type, sizeof(uint32_t)*6); - mav_array_memcpy(packet1.link_tx_rate, packet_in.link_tx_rate, sizeof(uint32_t)*6); - mav_array_memcpy(packet1.link_rx_rate, packet_in.link_rx_rate, sizeof(uint32_t)*6); - mav_array_memcpy(packet1.link_tx_max, packet_in.link_tx_max, sizeof(uint32_t)*6); - mav_array_memcpy(packet1.link_rx_max, packet_in.link_rx_max, sizeof(uint32_t)*6); - mav_array_memcpy(packet1.fan_speed, packet_in.fan_speed, sizeof(int16_t)*4); - mav_array_memcpy(packet1.cpu_cores, packet_in.cpu_cores, sizeof(uint8_t)*8); - mav_array_memcpy(packet1.cpu_combined, packet_in.cpu_combined, sizeof(uint8_t)*10); - mav_array_memcpy(packet1.gpu_cores, packet_in.gpu_cores, sizeof(uint8_t)*4); - mav_array_memcpy(packet1.gpu_combined, packet_in.gpu_combined, sizeof(uint8_t)*10); - mav_array_memcpy(packet1.temperature_core, packet_in.temperature_core, sizeof(int8_t)*8); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_ONBOARD_COMPUTER_STATUS_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_ONBOARD_COMPUTER_STATUS_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_onboard_computer_status_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_onboard_computer_status_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_onboard_computer_status_pack(system_id, component_id, &msg , packet1.time_usec , packet1.uptime , packet1.type , packet1.cpu_cores , packet1.cpu_combined , packet1.gpu_cores , packet1.gpu_combined , packet1.temperature_board , packet1.temperature_core , packet1.fan_speed , packet1.ram_usage , packet1.ram_total , packet1.storage_type , packet1.storage_usage , packet1.storage_total , packet1.link_type , packet1.link_tx_rate , packet1.link_rx_rate , packet1.link_tx_max , packet1.link_rx_max ); - mavlink_msg_onboard_computer_status_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_onboard_computer_status_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.uptime , packet1.type , packet1.cpu_cores , packet1.cpu_combined , packet1.gpu_cores , packet1.gpu_combined , packet1.temperature_board , packet1.temperature_core , packet1.fan_speed , packet1.ram_usage , packet1.ram_total , packet1.storage_type , packet1.storage_usage , packet1.storage_total , packet1.link_type , packet1.link_tx_rate , packet1.link_rx_rate , packet1.link_tx_max , packet1.link_rx_max ); - mavlink_msg_onboard_computer_status_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_COMPONENT_INFORMATION >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_component_information_t packet_in = { - 963497464,963497672,963497880,"MNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFG","IJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABC" - }; - mavlink_component_information_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_boot_ms = packet_in.time_boot_ms; - packet1.general_metadata_file_crc = packet_in.general_metadata_file_crc; - packet1.peripherals_metadata_file_crc = packet_in.peripherals_metadata_file_crc; - - mav_array_memcpy(packet1.general_metadata_uri, packet_in.general_metadata_uri, sizeof(char)*100); - mav_array_memcpy(packet1.peripherals_metadata_uri, packet_in.peripherals_metadata_uri, sizeof(char)*100); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_COMPONENT_INFORMATION_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_COMPONENT_INFORMATION_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_component_information_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_component_information_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_component_information_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.general_metadata_file_crc , packet1.general_metadata_uri , packet1.peripherals_metadata_file_crc , packet1.peripherals_metadata_uri ); - mavlink_msg_component_information_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_component_information_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.general_metadata_file_crc , packet1.general_metadata_uri , packet1.peripherals_metadata_file_crc , packet1.peripherals_metadata_uri ); - mavlink_msg_component_information_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_COMPONENT_METADATA >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_component_metadata_t packet_in = { - 963497464,963497672,"IJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABC" - }; - mavlink_component_metadata_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_boot_ms = packet_in.time_boot_ms; - packet1.file_crc = packet_in.file_crc; - - mav_array_memcpy(packet1.uri, packet_in.uri, sizeof(char)*100); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_COMPONENT_METADATA_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_COMPONENT_METADATA_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_component_metadata_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_component_metadata_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_component_metadata_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.file_crc , packet1.uri ); - mavlink_msg_component_metadata_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_component_metadata_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.file_crc , packet1.uri ); - mavlink_msg_component_metadata_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_PLAY_TUNE_V2 >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_play_tune_v2_t packet_in = { - 963497464,17,84,"GHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRS" - }; - mavlink_play_tune_v2_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.format = packet_in.format; - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - - mav_array_memcpy(packet1.tune, packet_in.tune, sizeof(char)*248); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_PLAY_TUNE_V2_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_PLAY_TUNE_V2_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_play_tune_v2_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_play_tune_v2_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_play_tune_v2_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.format , packet1.tune ); - mavlink_msg_play_tune_v2_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_play_tune_v2_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.format , packet1.tune ); - mavlink_msg_play_tune_v2_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_SUPPORTED_TUNES >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_supported_tunes_t packet_in = { - 963497464,17,84 - }; - mavlink_supported_tunes_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.format = packet_in.format; - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_SUPPORTED_TUNES_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SUPPORTED_TUNES_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_supported_tunes_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_supported_tunes_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_supported_tunes_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.format ); - mavlink_msg_supported_tunes_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_supported_tunes_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.format ); - mavlink_msg_supported_tunes_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_EVENT >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_event_t packet_in = { - 963497464,963497672,17651,163,230,41,{ 108, 109, 110, 111, 112, 113, 114, 115, 116, 117, 118, 119, 120, 121, 122, 123, 124, 125, 126, 127, 128, 129, 130, 131, 132, 133, 134, 135, 136, 137, 138, 139, 140, 141, 142, 143, 144, 145, 146, 147 } - }; - mavlink_event_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.id = packet_in.id; - packet1.event_time_boot_ms = packet_in.event_time_boot_ms; - packet1.sequence = packet_in.sequence; - packet1.destination_component = packet_in.destination_component; - packet1.destination_system = packet_in.destination_system; - packet1.log_levels = packet_in.log_levels; - - mav_array_memcpy(packet1.arguments, packet_in.arguments, sizeof(uint8_t)*40); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_EVENT_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_EVENT_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_event_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_event_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_event_pack(system_id, component_id, &msg , packet1.destination_component , packet1.destination_system , packet1.id , packet1.event_time_boot_ms , packet1.sequence , packet1.log_levels , packet1.arguments ); - mavlink_msg_event_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_event_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.destination_component , packet1.destination_system , packet1.id , packet1.event_time_boot_ms , packet1.sequence , packet1.log_levels , packet1.arguments ); - mavlink_msg_event_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_CURRENT_EVENT_SEQUENCE >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_current_event_sequence_t packet_in = { - 17235,139 - }; - mavlink_current_event_sequence_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.sequence = packet_in.sequence; - packet1.flags = packet_in.flags; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_CURRENT_EVENT_SEQUENCE_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_CURRENT_EVENT_SEQUENCE_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_current_event_sequence_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_current_event_sequence_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_current_event_sequence_pack(system_id, component_id, &msg , packet1.sequence , packet1.flags ); - mavlink_msg_current_event_sequence_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_current_event_sequence_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.sequence , packet1.flags ); - mavlink_msg_current_event_sequence_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_REQUEST_EVENT >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_request_event_t packet_in = { - 17235,17339,17,84 - }; - mavlink_request_event_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.first_sequence = packet_in.first_sequence; - packet1.last_sequence = packet_in.last_sequence; - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_REQUEST_EVENT_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_REQUEST_EVENT_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_request_event_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_request_event_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_request_event_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.first_sequence , packet1.last_sequence ); - mavlink_msg_request_event_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_request_event_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.first_sequence , packet1.last_sequence ); - mavlink_msg_request_event_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_RESPONSE_EVENT_ERROR >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_response_event_error_t packet_in = { - 17235,17339,17,84,151 - }; - mavlink_response_event_error_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.sequence = packet_in.sequence; - packet1.sequence_oldest_available = packet_in.sequence_oldest_available; - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - packet1.reason = packet_in.reason; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_RESPONSE_EVENT_ERROR_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_RESPONSE_EVENT_ERROR_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_response_event_error_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_response_event_error_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_response_event_error_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.sequence , packet1.sequence_oldest_available , packet1.reason ); - mavlink_msg_response_event_error_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_response_event_error_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.sequence , packet1.sequence_oldest_available , packet1.reason ); - mavlink_msg_response_event_error_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_CANFD_FRAME >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_canfd_frame_t packet_in = { - 963497464,17,84,151,218,{ 29, 30, 31, 32, 33, 34, 35, 36, 37, 38, 39, 40, 41, 42, 43, 44, 45, 46, 47, 48, 49, 50, 51, 52, 53, 54, 55, 56, 57, 58, 59, 60, 61, 62, 63, 64, 65, 66, 67, 68, 69, 70, 71, 72, 73, 74, 75, 76, 77, 78, 79, 80, 81, 82, 83, 84, 85, 86, 87, 88, 89, 90, 91, 92 } - }; - mavlink_canfd_frame_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.id = packet_in.id; - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - packet1.bus = packet_in.bus; - packet1.len = packet_in.len; - - mav_array_memcpy(packet1.data, packet_in.data, sizeof(uint8_t)*64); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_CANFD_FRAME_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_CANFD_FRAME_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_canfd_frame_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_canfd_frame_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_canfd_frame_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.bus , packet1.len , packet1.id , packet1.data ); - mavlink_msg_canfd_frame_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_canfd_frame_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.bus , packet1.len , packet1.id , packet1.data ); - mavlink_msg_canfd_frame_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_CAN_FILTER_MODIFY >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_can_filter_modify_t packet_in = { - { 17235, 17236, 17237, 17238, 17239, 17240, 17241, 17242, 17243, 17244, 17245, 17246, 17247, 17248, 17249, 17250 },101,168,235,46,113 - }; - mavlink_can_filter_modify_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - packet1.bus = packet_in.bus; - packet1.operation = packet_in.operation; - packet1.num_ids = packet_in.num_ids; - - mav_array_memcpy(packet1.ids, packet_in.ids, sizeof(uint16_t)*16); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_CAN_FILTER_MODIFY_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_CAN_FILTER_MODIFY_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_can_filter_modify_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_can_filter_modify_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_can_filter_modify_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.bus , packet1.operation , packet1.num_ids , packet1.ids ); - mavlink_msg_can_filter_modify_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_can_filter_modify_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.bus , packet1.operation , packet1.num_ids , packet1.ids ); - mavlink_msg_can_filter_modify_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_WHEEL_DISTANCE >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_wheel_distance_t packet_in = { - 93372036854775807ULL,{ 179.0, 180.0, 181.0, 182.0, 183.0, 184.0, 185.0, 186.0, 187.0, 188.0, 189.0, 190.0, 191.0, 192.0, 193.0, 194.0 },157 - }; - mavlink_wheel_distance_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_usec = packet_in.time_usec; - packet1.count = packet_in.count; - - mav_array_memcpy(packet1.distance, packet_in.distance, sizeof(double)*16); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_WHEEL_DISTANCE_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_WHEEL_DISTANCE_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_wheel_distance_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_wheel_distance_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_wheel_distance_pack(system_id, component_id, &msg , packet1.time_usec , packet1.count , packet1.distance ); - mavlink_msg_wheel_distance_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_wheel_distance_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.count , packet1.distance ); - mavlink_msg_wheel_distance_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_WINCH_STATUS >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_winch_status_t packet_in = { - 93372036854775807ULL,73.0,101.0,129.0,157.0,185.0,963498920,18899 - }; - mavlink_winch_status_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.time_usec = packet_in.time_usec; - packet1.line_length = packet_in.line_length; - packet1.speed = packet_in.speed; - packet1.tension = packet_in.tension; - packet1.voltage = packet_in.voltage; - packet1.current = packet_in.current; - packet1.status = packet_in.status; - packet1.temperature = packet_in.temperature; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_WINCH_STATUS_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_WINCH_STATUS_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_winch_status_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_winch_status_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_winch_status_pack(system_id, component_id, &msg , packet1.time_usec , packet1.line_length , packet1.speed , packet1.tension , packet1.voltage , packet1.current , packet1.temperature , packet1.status ); - mavlink_msg_winch_status_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_winch_status_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.line_length , packet1.speed , packet1.tension , packet1.voltage , packet1.current , packet1.temperature , packet1.status ); - mavlink_msg_winch_status_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_OPEN_DRONE_ID_BASIC_ID >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_open_drone_id_basic_id_t packet_in = { - 5,72,{ 139, 140, 141, 142, 143, 144, 145, 146, 147, 148, 149, 150, 151, 152, 153, 154, 155, 156, 157, 158 },199,10,{ 77, 78, 79, 80, 81, 82, 83, 84, 85, 86, 87, 88, 89, 90, 91, 92, 93, 94, 95, 96 } - }; - mavlink_open_drone_id_basic_id_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - packet1.id_type = packet_in.id_type; - packet1.ua_type = packet_in.ua_type; - - mav_array_memcpy(packet1.id_or_mac, packet_in.id_or_mac, sizeof(uint8_t)*20); - mav_array_memcpy(packet1.uas_id, packet_in.uas_id, sizeof(uint8_t)*20); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_OPEN_DRONE_ID_BASIC_ID_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_OPEN_DRONE_ID_BASIC_ID_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_open_drone_id_basic_id_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_open_drone_id_basic_id_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_open_drone_id_basic_id_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.id_or_mac , packet1.id_type , packet1.ua_type , packet1.uas_id ); - mavlink_msg_open_drone_id_basic_id_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_open_drone_id_basic_id_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.id_or_mac , packet1.id_type , packet1.ua_type , packet1.uas_id ); - mavlink_msg_open_drone_id_basic_id_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_OPEN_DRONE_ID_LOCATION >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_open_drone_id_location_t packet_in = { - 963497464,963497672,73.0,101.0,129.0,157.0,18483,18587,18691,223,34,{ 101, 102, 103, 104, 105, 106, 107, 108, 109, 110, 111, 112, 113, 114, 115, 116, 117, 118, 119, 120 },161,228,39,106,173,240,51 - }; - mavlink_open_drone_id_location_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.latitude = packet_in.latitude; - packet1.longitude = packet_in.longitude; - packet1.altitude_barometric = packet_in.altitude_barometric; - packet1.altitude_geodetic = packet_in.altitude_geodetic; - packet1.height = packet_in.height; - packet1.timestamp = packet_in.timestamp; - packet1.direction = packet_in.direction; - packet1.speed_horizontal = packet_in.speed_horizontal; - packet1.speed_vertical = packet_in.speed_vertical; - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - packet1.status = packet_in.status; - packet1.height_reference = packet_in.height_reference; - packet1.horizontal_accuracy = packet_in.horizontal_accuracy; - packet1.vertical_accuracy = packet_in.vertical_accuracy; - packet1.barometer_accuracy = packet_in.barometer_accuracy; - packet1.speed_accuracy = packet_in.speed_accuracy; - packet1.timestamp_accuracy = packet_in.timestamp_accuracy; - - mav_array_memcpy(packet1.id_or_mac, packet_in.id_or_mac, sizeof(uint8_t)*20); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_OPEN_DRONE_ID_LOCATION_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_OPEN_DRONE_ID_LOCATION_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_open_drone_id_location_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_open_drone_id_location_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_open_drone_id_location_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.id_or_mac , packet1.status , packet1.direction , packet1.speed_horizontal , packet1.speed_vertical , packet1.latitude , packet1.longitude , packet1.altitude_barometric , packet1.altitude_geodetic , packet1.height_reference , packet1.height , packet1.horizontal_accuracy , packet1.vertical_accuracy , packet1.barometer_accuracy , packet1.speed_accuracy , packet1.timestamp , packet1.timestamp_accuracy ); - mavlink_msg_open_drone_id_location_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_open_drone_id_location_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.id_or_mac , packet1.status , packet1.direction , packet1.speed_horizontal , packet1.speed_vertical , packet1.latitude , packet1.longitude , packet1.altitude_barometric , packet1.altitude_geodetic , packet1.height_reference , packet1.height , packet1.horizontal_accuracy , packet1.vertical_accuracy , packet1.barometer_accuracy , packet1.speed_accuracy , packet1.timestamp , packet1.timestamp_accuracy ); - mavlink_msg_open_drone_id_location_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_OPEN_DRONE_ID_AUTHENTICATION >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_open_drone_id_authentication_t packet_in = { - 963497464,17,84,{ 151, 152, 153, 154, 155, 156, 157, 158, 159, 160, 161, 162, 163, 164, 165, 166, 167, 168, 169, 170 },211,22,89,156,{ 223, 224, 225, 226, 227, 228, 229, 230, 231, 232, 233, 234, 235, 236, 237, 238, 239, 240, 241, 242, 243, 244, 245 } - }; - mavlink_open_drone_id_authentication_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.timestamp = packet_in.timestamp; - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - packet1.authentication_type = packet_in.authentication_type; - packet1.data_page = packet_in.data_page; - packet1.last_page_index = packet_in.last_page_index; - packet1.length = packet_in.length; - - mav_array_memcpy(packet1.id_or_mac, packet_in.id_or_mac, sizeof(uint8_t)*20); - mav_array_memcpy(packet1.authentication_data, packet_in.authentication_data, sizeof(uint8_t)*23); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_OPEN_DRONE_ID_AUTHENTICATION_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_OPEN_DRONE_ID_AUTHENTICATION_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_open_drone_id_authentication_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_open_drone_id_authentication_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_open_drone_id_authentication_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.id_or_mac , packet1.authentication_type , packet1.data_page , packet1.last_page_index , packet1.length , packet1.timestamp , packet1.authentication_data ); - mavlink_msg_open_drone_id_authentication_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_open_drone_id_authentication_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.id_or_mac , packet1.authentication_type , packet1.data_page , packet1.last_page_index , packet1.length , packet1.timestamp , packet1.authentication_data ); - mavlink_msg_open_drone_id_authentication_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_OPEN_DRONE_ID_SELF_ID >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_open_drone_id_self_id_t packet_in = { - 5,72,{ 139, 140, 141, 142, 143, 144, 145, 146, 147, 148, 149, 150, 151, 152, 153, 154, 155, 156, 157, 158 },199,"XYZABCDEFGHIJKLMNOPQRS" - }; - mavlink_open_drone_id_self_id_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - packet1.description_type = packet_in.description_type; - - mav_array_memcpy(packet1.id_or_mac, packet_in.id_or_mac, sizeof(uint8_t)*20); - mav_array_memcpy(packet1.description, packet_in.description, sizeof(char)*23); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_OPEN_DRONE_ID_SELF_ID_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_OPEN_DRONE_ID_SELF_ID_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_open_drone_id_self_id_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_open_drone_id_self_id_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_open_drone_id_self_id_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.id_or_mac , packet1.description_type , packet1.description ); - mavlink_msg_open_drone_id_self_id_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_open_drone_id_self_id_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.id_or_mac , packet1.description_type , packet1.description ); - mavlink_msg_open_drone_id_self_id_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_open_drone_id_system_t packet_in = { - 963497464,963497672,73.0,101.0,129.0,963498504,18483,18587,89,156,{ 223, 224, 225, 226, 227, 228, 229, 230, 231, 232, 233, 234, 235, 236, 237, 238, 239, 240, 241, 242 },27,94,161,228 - }; - mavlink_open_drone_id_system_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.operator_latitude = packet_in.operator_latitude; - packet1.operator_longitude = packet_in.operator_longitude; - packet1.area_ceiling = packet_in.area_ceiling; - packet1.area_floor = packet_in.area_floor; - packet1.operator_altitude_geo = packet_in.operator_altitude_geo; - packet1.timestamp = packet_in.timestamp; - packet1.area_count = packet_in.area_count; - packet1.area_radius = packet_in.area_radius; - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - packet1.operator_location_type = packet_in.operator_location_type; - packet1.classification_type = packet_in.classification_type; - packet1.category_eu = packet_in.category_eu; - packet1.class_eu = packet_in.class_eu; - - mav_array_memcpy(packet1.id_or_mac, packet_in.id_or_mac, sizeof(uint8_t)*20); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_open_drone_id_system_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_open_drone_id_system_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_open_drone_id_system_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.id_or_mac , packet1.operator_location_type , packet1.classification_type , packet1.operator_latitude , packet1.operator_longitude , packet1.area_count , packet1.area_radius , packet1.area_ceiling , packet1.area_floor , packet1.category_eu , packet1.class_eu , packet1.operator_altitude_geo , packet1.timestamp ); - mavlink_msg_open_drone_id_system_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_open_drone_id_system_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.id_or_mac , packet1.operator_location_type , packet1.classification_type , packet1.operator_latitude , packet1.operator_longitude , packet1.area_count , packet1.area_radius , packet1.area_ceiling , packet1.area_floor , packet1.category_eu , packet1.class_eu , packet1.operator_altitude_geo , packet1.timestamp ); - mavlink_msg_open_drone_id_system_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_OPEN_DRONE_ID_OPERATOR_ID >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_open_drone_id_operator_id_t packet_in = { - 5,72,{ 139, 140, 141, 142, 143, 144, 145, 146, 147, 148, 149, 150, 151, 152, 153, 154, 155, 156, 157, 158 },199,"XYZABCDEFGHIJKLMNOP" - }; - mavlink_open_drone_id_operator_id_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - packet1.operator_id_type = packet_in.operator_id_type; - - mav_array_memcpy(packet1.id_or_mac, packet_in.id_or_mac, sizeof(uint8_t)*20); - mav_array_memcpy(packet1.operator_id, packet_in.operator_id, sizeof(char)*20); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_OPEN_DRONE_ID_OPERATOR_ID_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_OPEN_DRONE_ID_OPERATOR_ID_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_open_drone_id_operator_id_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_open_drone_id_operator_id_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_open_drone_id_operator_id_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.id_or_mac , packet1.operator_id_type , packet1.operator_id ); - mavlink_msg_open_drone_id_operator_id_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_open_drone_id_operator_id_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.id_or_mac , packet1.operator_id_type , packet1.operator_id ); - mavlink_msg_open_drone_id_operator_id_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_OPEN_DRONE_ID_MESSAGE_PACK >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_open_drone_id_message_pack_t packet_in = { - 5,72,{ 139, 140, 141, 142, 143, 144, 145, 146, 147, 148, 149, 150, 151, 152, 153, 154, 155, 156, 157, 158 },199,10,{ 77, 78, 79, 80, 81, 82, 83, 84, 85, 86, 87, 88, 89, 90, 91, 92, 93, 94, 95, 96, 97, 98, 99, 100, 101, 102, 103, 104, 105, 106, 107, 108, 109, 110, 111, 112, 113, 114, 115, 116, 117, 118, 119, 120, 121, 122, 123, 124, 125, 126, 127, 128, 129, 130, 131, 132, 133, 134, 135, 136, 137, 138, 139, 140, 141, 142, 143, 144, 145, 146, 147, 148, 149, 150, 151, 152, 153, 154, 155, 156, 157, 158, 159, 160, 161, 162, 163, 164, 165, 166, 167, 168, 169, 170, 171, 172, 173, 174, 175, 176, 177, 178, 179, 180, 181, 182, 183, 184, 185, 186, 187, 188, 189, 190, 191, 192, 193, 194, 195, 196, 197, 198, 199, 200, 201, 202, 203, 204, 205, 206, 207, 208, 209, 210, 211, 212, 213, 214, 215, 216, 217, 218, 219, 220, 221, 222, 223, 224, 225, 226, 227, 228, 229, 230, 231, 232, 233, 234, 235, 236, 237, 238, 239, 240, 241, 242, 243, 244, 245, 246, 247, 248, 249, 250, 251, 252, 253, 254, 255, 0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31, 32, 33, 34, 35, 36, 37, 38, 39, 40, 41, 42, 43, 44, 45 } - }; - mavlink_open_drone_id_message_pack_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - packet1.single_message_size = packet_in.single_message_size; - packet1.msg_pack_size = packet_in.msg_pack_size; - - mav_array_memcpy(packet1.id_or_mac, packet_in.id_or_mac, sizeof(uint8_t)*20); - mav_array_memcpy(packet1.messages, packet_in.messages, sizeof(uint8_t)*225); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_OPEN_DRONE_ID_MESSAGE_PACK_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_OPEN_DRONE_ID_MESSAGE_PACK_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_open_drone_id_message_pack_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_open_drone_id_message_pack_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_open_drone_id_message_pack_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.id_or_mac , packet1.single_message_size , packet1.msg_pack_size , packet1.messages ); - mavlink_msg_open_drone_id_message_pack_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_open_drone_id_message_pack_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.id_or_mac , packet1.single_message_size , packet1.msg_pack_size , packet1.messages ); - mavlink_msg_open_drone_id_message_pack_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_OPEN_DRONE_ID_ARM_STATUS >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_open_drone_id_arm_status_t packet_in = { - 5,"BCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWX" - }; - mavlink_open_drone_id_arm_status_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.status = packet_in.status; - - mav_array_memcpy(packet1.error, packet_in.error, sizeof(char)*50); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_OPEN_DRONE_ID_ARM_STATUS_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_OPEN_DRONE_ID_ARM_STATUS_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_open_drone_id_arm_status_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_open_drone_id_arm_status_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_open_drone_id_arm_status_pack(system_id, component_id, &msg , packet1.status , packet1.error ); - mavlink_msg_open_drone_id_arm_status_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_open_drone_id_arm_status_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.status , packet1.error ); - mavlink_msg_open_drone_id_arm_status_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_UPDATE >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_open_drone_id_system_update_t packet_in = { - 963497464,963497672,73.0,963498088,53,120 - }; - mavlink_open_drone_id_system_update_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.operator_latitude = packet_in.operator_latitude; - packet1.operator_longitude = packet_in.operator_longitude; - packet1.operator_altitude_geo = packet_in.operator_altitude_geo; - packet1.timestamp = packet_in.timestamp; - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_UPDATE_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_UPDATE_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_open_drone_id_system_update_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_open_drone_id_system_update_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_open_drone_id_system_update_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.operator_latitude , packet1.operator_longitude , packet1.operator_altitude_geo , packet1.timestamp ); - mavlink_msg_open_drone_id_system_update_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_open_drone_id_system_update_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.operator_latitude , packet1.operator_longitude , packet1.operator_altitude_geo , packet1.timestamp ); - mavlink_msg_open_drone_id_system_update_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_HYGROMETER_SENSOR >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_hygrometer_sensor_t packet_in = { - 17235,17339,17 - }; - mavlink_hygrometer_sensor_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.temperature = packet_in.temperature; - packet1.humidity = packet_in.humidity; - packet1.id = packet_in.id; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_HYGROMETER_SENSOR_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_HYGROMETER_SENSOR_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_hygrometer_sensor_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_hygrometer_sensor_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_hygrometer_sensor_pack(system_id, component_id, &msg , packet1.id , packet1.temperature , packet1.humidity ); - mavlink_msg_hygrometer_sensor_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_hygrometer_sensor_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.id , packet1.temperature , packet1.humidity ); - mavlink_msg_hygrometer_sensor_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; i - -#ifndef M_PI_2 - #define M_PI_2 ((float)asin(1)) -#endif - -/** - * @file mavlink_conversions.h - * - * These conversion functions follow the NASA rotation standards definition file - * available online. - * - * Their intent is to lower the barrier for MAVLink adopters to use gimbal-lock free - * (both rotation matrices, sometimes called DCM, and quaternions are gimbal-lock free) - * rotation representations. Euler angles (roll, pitch, yaw) will be phased out of the - * protocol as widely as possible. - * - * @author James Goppert - * @author Thomas Gubler - */ - - -/** - * Converts a quaternion to a rotation matrix - * - * @param quaternion a [w, x, y, z] ordered quaternion (null-rotation being 1 0 0 0) - * @param dcm a 3x3 rotation matrix - */ -MAVLINK_HELPER void mavlink_quaternion_to_dcm(const float quaternion[4], float dcm[3][3]) -{ - double a = (double)quaternion[0]; - double b = (double)quaternion[1]; - double c = (double)quaternion[2]; - double d = (double)quaternion[3]; - double aSq = a * a; - double bSq = b * b; - double cSq = c * c; - double dSq = d * d; - dcm[0][0] = aSq + bSq - cSq - dSq; - dcm[0][1] = 2 * (b * c - a * d); - dcm[0][2] = 2 * (a * c + b * d); - dcm[1][0] = 2 * (b * c + a * d); - dcm[1][1] = aSq - bSq + cSq - dSq; - dcm[1][2] = 2 * (c * d - a * b); - dcm[2][0] = 2 * (b * d - a * c); - dcm[2][1] = 2 * (a * b + c * d); - dcm[2][2] = aSq - bSq - cSq + dSq; -} - - -/** - * Converts a rotation matrix to euler angles - * - * @param dcm a 3x3 rotation matrix - * @param roll the roll angle in radians - * @param pitch the pitch angle in radians - * @param yaw the yaw angle in radians - */ -MAVLINK_HELPER void mavlink_dcm_to_euler(const float dcm[3][3], float* roll, float* pitch, float* yaw) -{ - float phi, theta, psi; - theta = asinf(-dcm[2][0]); - - if (fabsf(theta - (float)M_PI_2) < 1.0e-3f) { - phi = 0.0f; - psi = (atan2f(dcm[1][2] - dcm[0][1], - dcm[0][2] + dcm[1][1]) + phi); - - } else if (fabsf(theta + (float)M_PI_2) < 1.0e-3f) { - phi = 0.0f; - psi = atan2f(dcm[1][2] - dcm[0][1], - dcm[0][2] + dcm[1][1] - phi); - - } else { - phi = atan2f(dcm[2][1], dcm[2][2]); - psi = atan2f(dcm[1][0], dcm[0][0]); - } - - *roll = phi; - *pitch = theta; - *yaw = psi; -} - - -/** - * Converts a quaternion to euler angles - * - * @param quaternion a [w, x, y, z] ordered quaternion (null-rotation being 1 0 0 0) - * @param roll the roll angle in radians - * @param pitch the pitch angle in radians - * @param yaw the yaw angle in radians - */ -MAVLINK_HELPER void mavlink_quaternion_to_euler(const float quaternion[4], float* roll, float* pitch, float* yaw) -{ - float dcm[3][3]; - mavlink_quaternion_to_dcm(quaternion, dcm); - mavlink_dcm_to_euler((const float(*)[3])dcm, roll, pitch, yaw); -} - - -/** - * Converts euler angles to a quaternion - * - * @param roll the roll angle in radians - * @param pitch the pitch angle in radians - * @param yaw the yaw angle in radians - * @param quaternion a [w, x, y, z] ordered quaternion (null-rotation being 1 0 0 0) - */ -MAVLINK_HELPER void mavlink_euler_to_quaternion(float roll, float pitch, float yaw, float quaternion[4]) -{ - float cosPhi_2 = cosf(roll / 2); - float sinPhi_2 = sinf(roll / 2); - float cosTheta_2 = cosf(pitch / 2); - float sinTheta_2 = sinf(pitch / 2); - float cosPsi_2 = cosf(yaw / 2); - float sinPsi_2 = sinf(yaw / 2); - quaternion[0] = (cosPhi_2 * cosTheta_2 * cosPsi_2 + - sinPhi_2 * sinTheta_2 * sinPsi_2); - quaternion[1] = (sinPhi_2 * cosTheta_2 * cosPsi_2 - - cosPhi_2 * sinTheta_2 * sinPsi_2); - quaternion[2] = (cosPhi_2 * sinTheta_2 * cosPsi_2 + - sinPhi_2 * cosTheta_2 * sinPsi_2); - quaternion[3] = (cosPhi_2 * cosTheta_2 * sinPsi_2 - - sinPhi_2 * sinTheta_2 * cosPsi_2); -} - - -/** - * Converts a rotation matrix to a quaternion - * Reference: - * - Shoemake, Quaternions, - * http://www.cs.ucr.edu/~vbz/resources/quatut.pdf - * - * @param dcm a 3x3 rotation matrix - * @param quaternion a [w, x, y, z] ordered quaternion (null-rotation being 1 0 0 0) - */ -MAVLINK_HELPER void mavlink_dcm_to_quaternion(const float dcm[3][3], float quaternion[4]) -{ - float tr = dcm[0][0] + dcm[1][1] + dcm[2][2]; - if (tr > 0.0f) { - float s = sqrtf(tr + 1.0f); - quaternion[0] = s * 0.5f; - s = 0.5f / s; - quaternion[1] = (dcm[2][1] - dcm[1][2]) * s; - quaternion[2] = (dcm[0][2] - dcm[2][0]) * s; - quaternion[3] = (dcm[1][0] - dcm[0][1]) * s; - } else { - /* Find maximum diagonal element in dcm - * store index in dcm_i */ - int dcm_i = 0; - int i; - for (i = 1; i < 3; i++) { - if (dcm[i][i] > dcm[dcm_i][dcm_i]) { - dcm_i = i; - } - } - - int dcm_j = (dcm_i + 1) % 3; - int dcm_k = (dcm_i + 2) % 3; - - float s = sqrtf((dcm[dcm_i][dcm_i] - dcm[dcm_j][dcm_j] - - dcm[dcm_k][dcm_k]) + 1.0f); - quaternion[dcm_i + 1] = s * 0.5f; - s = 0.5f / s; - quaternion[dcm_j + 1] = (dcm[dcm_i][dcm_j] + dcm[dcm_j][dcm_i]) * s; - quaternion[dcm_k + 1] = (dcm[dcm_k][dcm_i] + dcm[dcm_i][dcm_k]) * s; - quaternion[0] = (dcm[dcm_k][dcm_j] - dcm[dcm_j][dcm_k]) * s; - } -} - - -/** - * Converts euler angles to a rotation matrix - * - * @param roll the roll angle in radians - * @param pitch the pitch angle in radians - * @param yaw the yaw angle in radians - * @param dcm a 3x3 rotation matrix - */ -MAVLINK_HELPER void mavlink_euler_to_dcm(float roll, float pitch, float yaw, float dcm[3][3]) -{ - float cosPhi = cosf(roll); - float sinPhi = sinf(roll); - float cosThe = cosf(pitch); - float sinThe = sinf(pitch); - float cosPsi = cosf(yaw); - float sinPsi = sinf(yaw); - - dcm[0][0] = cosThe * cosPsi; - dcm[0][1] = -cosPhi * sinPsi + sinPhi * sinThe * cosPsi; - dcm[0][2] = sinPhi * sinPsi + cosPhi * sinThe * cosPsi; - - dcm[1][0] = cosThe * sinPsi; - dcm[1][1] = cosPhi * cosPsi + sinPhi * sinThe * sinPsi; - dcm[1][2] = -sinPhi * cosPsi + cosPhi * sinThe * sinPsi; - - dcm[2][0] = -sinThe; - dcm[2][1] = sinPhi * cosThe; - dcm[2][2] = cosPhi * cosThe; -} - -#endif // MAVLINK_NO_CONVERSION_HELPERS diff --git a/TelemetryManager/Inc/official_mavlink_2_library/mavlink_get_info.h b/TelemetryManager/Inc/official_mavlink_2_library/mavlink_get_info.h deleted file mode 100644 index 302ec8bd..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/mavlink_get_info.h +++ /dev/null @@ -1,83 +0,0 @@ -#pragma once - -#ifdef MAVLINK_USE_MESSAGE_INFO -#define MAVLINK_HAVE_GET_MESSAGE_INFO - -/* - return the message_info struct for a message -*/ -MAVLINK_HELPER const mavlink_message_info_t *mavlink_get_message_info_by_id(uint32_t msgid) -{ - static const mavlink_message_info_t mavlink_message_info[] = MAVLINK_MESSAGE_INFO; - /* - use a bisection search to find the right entry. A perfect hash may be better - Note that this assumes the table is sorted with primary key msgid - */ - const uint32_t count = sizeof(mavlink_message_info)/sizeof(mavlink_message_info[0]); - if (count == 0) { - return NULL; - } - uint32_t low=0, high=count-1; - while (low < high) { - uint32_t mid = (low+high)/2; - if (msgid < mavlink_message_info[mid].msgid) { - high = mid; - continue; - } - if (msgid > mavlink_message_info[mid].msgid) { - low = mid+1; - continue; - } - return &mavlink_message_info[mid]; - } - if (mavlink_message_info[low].msgid == msgid) { - return &mavlink_message_info[low]; - } - return NULL; -} - -/* - return the message_info struct for a message -*/ -MAVLINK_HELPER const mavlink_message_info_t *mavlink_get_message_info(const mavlink_message_t *msg) -{ - return mavlink_get_message_info_by_id(msg->msgid); -} - -/* - return the message_info struct for a message -*/ -MAVLINK_HELPER const mavlink_message_info_t *mavlink_get_message_info_by_name(const char *name) -{ - static const struct { const char *name; uint32_t msgid; } mavlink_message_names[] = MAVLINK_MESSAGE_NAMES; - /* - use a bisection search to find the right entry. A perfect hash may be better - Note that this assumes the table is sorted with primary key name - */ - const uint32_t count = sizeof(mavlink_message_names)/sizeof(mavlink_message_names[0]); - if (count == 0) { - return NULL; - } - uint32_t low=0, high=count-1; - while (low < high) { - uint32_t mid = (low+high)/2; - int cmp = strcmp(mavlink_message_names[mid].name, name); - if (cmp > 0) { - high = mid; - continue; - } - if (cmp < 0) { - low = mid+1; - continue; - } - low = mid; - break; - } - if (strcmp(mavlink_message_names[low].name, name) == 0) { - return mavlink_get_message_info_by_id(mavlink_message_names[low].msgid); - } - return NULL; -} -#endif // MAVLINK_USE_MESSAGE_INFO - - diff --git a/TelemetryManager/Inc/official_mavlink_2_library/mavlink_helpers.h b/TelemetryManager/Inc/official_mavlink_2_library/mavlink_helpers.h deleted file mode 100644 index b36f51e4..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/mavlink_helpers.h +++ /dev/null @@ -1,1154 +0,0 @@ -#pragma once - -#include "string.h" -#include "checksum.h" -#include "mavlink_types.h" -#include "mavlink_conversions.h" -#include - -#ifndef MAVLINK_HELPER -#define MAVLINK_HELPER -#endif - -#include "mavlink_sha256.h" - -#ifdef MAVLINK_USE_CXX_NAMESPACE -namespace mavlink { -#endif - -/* - * Internal function to give access to the channel status for each channel - */ -#ifndef MAVLINK_GET_CHANNEL_STATUS -MAVLINK_HELPER mavlink_status_t* mavlink_get_channel_status(uint8_t chan) -{ -#ifdef MAVLINK_EXTERNAL_RX_STATUS - // No m_mavlink_status array defined in function, - // has to be defined externally -#else - static mavlink_status_t m_mavlink_status[MAVLINK_COMM_NUM_BUFFERS]; -#endif - return &m_mavlink_status[chan]; -} -#endif - -/* - * Internal function to give access to the channel buffer for each channel - */ -#ifndef MAVLINK_GET_CHANNEL_BUFFER -MAVLINK_HELPER mavlink_message_t* mavlink_get_channel_buffer(uint8_t chan) -{ - -#ifdef MAVLINK_EXTERNAL_RX_BUFFER - // No m_mavlink_buffer array defined in function, - // has to be defined externally -#else - static mavlink_message_t m_mavlink_buffer[MAVLINK_COMM_NUM_BUFFERS]; -#endif - return &m_mavlink_buffer[chan]; -} -#endif // MAVLINK_GET_CHANNEL_BUFFER - -/* Enable this option to check the length of each message. - This allows invalid messages to be caught much sooner. Use if the transmission - medium is prone to missing (or extra) characters (e.g. a radio that fades in - and out). Only use if the channel will only contain messages types listed in - the headers. -*/ -//#define MAVLINK_CHECK_MESSAGE_LENGTH - -/** - * @brief Reset the status of a channel. - */ -MAVLINK_HELPER void mavlink_reset_channel_status(uint8_t chan) -{ - mavlink_status_t *status = mavlink_get_channel_status(chan); - status->parse_state = MAVLINK_PARSE_STATE_IDLE; -} - -#ifndef MAVLINK_NO_SIGN_PACKET -/** - * @brief create a signature block for a packet - */ -MAVLINK_HELPER uint8_t mavlink_sign_packet(mavlink_signing_t *signing, - uint8_t signature[MAVLINK_SIGNATURE_BLOCK_LEN], - const uint8_t *header, uint8_t header_len, - const uint8_t *packet, uint8_t packet_len, - const uint8_t crc[2]) -{ - mavlink_sha256_ctx ctx; - union { - uint64_t t64; - uint8_t t8[8]; - } tstamp; - if (signing == NULL || !(signing->flags & MAVLINK_SIGNING_FLAG_SIGN_OUTGOING)) { - return 0; - } - signature[0] = signing->link_id; - tstamp.t64 = signing->timestamp; - memcpy(&signature[1], tstamp.t8, 6); - signing->timestamp++; - - mavlink_sha256_init(&ctx); - mavlink_sha256_update(&ctx, signing->secret_key, sizeof(signing->secret_key)); - mavlink_sha256_update(&ctx, header, header_len); - mavlink_sha256_update(&ctx, packet, packet_len); - mavlink_sha256_update(&ctx, crc, 2); - mavlink_sha256_update(&ctx, signature, 7); - mavlink_sha256_final_48(&ctx, &signature[7]); - - return MAVLINK_SIGNATURE_BLOCK_LEN; -} -#endif - -/** - * @brief Trim payload of any trailing zero-populated bytes (MAVLink 2 only). - * - * @param payload Serialised payload buffer. - * @param length Length of full-width payload buffer. - * @return Length of payload after zero-filled bytes are trimmed. - */ -MAVLINK_HELPER uint8_t _mav_trim_payload(const char *payload, uint8_t length) -{ - while (length > 1 && payload[length-1] == 0) { - length--; - } - return length; -} - -#ifndef MAVLINK_NO_SIGNATURE_CHECK -/** - * @brief check a signature block for a packet - */ -MAVLINK_HELPER bool mavlink_signature_check(mavlink_signing_t *signing, - mavlink_signing_streams_t *signing_streams, - const mavlink_message_t *msg) -{ - if (signing == NULL) { - return true; - } - const uint8_t *p = (const uint8_t *)&msg->magic; - const uint8_t *psig = msg->signature; - const uint8_t *incoming_signature = psig+7; - mavlink_sha256_ctx ctx; - uint8_t signature[6]; - uint16_t i; - - mavlink_sha256_init(&ctx); - mavlink_sha256_update(&ctx, signing->secret_key, sizeof(signing->secret_key)); - mavlink_sha256_update(&ctx, p, MAVLINK_NUM_HEADER_BYTES); - mavlink_sha256_update(&ctx, _MAV_PAYLOAD(msg), msg->len); - mavlink_sha256_update(&ctx, msg->ck, 2); - mavlink_sha256_update(&ctx, psig, 1+6); - mavlink_sha256_final_48(&ctx, signature); - if (memcmp(signature, incoming_signature, 6) != 0) { - signing->last_status = MAVLINK_SIGNING_STATUS_BAD_SIGNATURE; - return false; - } - - // now check timestamp - union tstamp { - uint64_t t64; - uint8_t t8[8]; - } tstamp; - uint8_t link_id = psig[0]; - tstamp.t64 = 0; - memcpy(tstamp.t8, psig+1, 6); - - if (signing_streams == NULL) { - signing->last_status = MAVLINK_SIGNING_STATUS_NO_STREAMS; - return false; - } - - // find stream - for (i=0; inum_signing_streams; i++) { - if (msg->sysid == signing_streams->stream[i].sysid && - msg->compid == signing_streams->stream[i].compid && - link_id == signing_streams->stream[i].link_id) { - break; - } - } - if (i == signing_streams->num_signing_streams) { - if (signing_streams->num_signing_streams >= MAVLINK_MAX_SIGNING_STREAMS) { - // over max number of streams - signing->last_status = MAVLINK_SIGNING_STATUS_TOO_MANY_STREAMS; - return false; - } - // new stream. Only accept if timestamp is not more than 1 minute old - if (tstamp.t64 + 6000*1000UL < signing->timestamp) { - signing->last_status = MAVLINK_SIGNING_STATUS_OLD_TIMESTAMP; - return false; - } - // add new stream - signing_streams->stream[i].sysid = msg->sysid; - signing_streams->stream[i].compid = msg->compid; - signing_streams->stream[i].link_id = link_id; - signing_streams->num_signing_streams++; - } else { - union tstamp last_tstamp; - last_tstamp.t64 = 0; - memcpy(last_tstamp.t8, signing_streams->stream[i].timestamp_bytes, 6); - if (tstamp.t64 <= last_tstamp.t64) { - // repeating old timestamp - signing->last_status = MAVLINK_SIGNING_STATUS_REPLAY; - return false; - } - } - - // remember last timestamp - memcpy(signing_streams->stream[i].timestamp_bytes, psig+1, 6); - - // our next timestamp must be at least this timestamp - if (tstamp.t64 > signing->timestamp) { - signing->timestamp = tstamp.t64; - } - signing->last_status = MAVLINK_SIGNING_STATUS_OK; - return true; -} -#endif - - -/** - * @brief Finalize a MAVLink message with channel assignment - * - * This function calculates the checksum and sets length and aircraft id correctly. - * It assumes that the message id and the payload are already correctly set. This function - * can also be used if the message header has already been written before (as in mavlink_msg_xxx_pack - * instead of mavlink_msg_xxx_pack_headerless), it just introduces little extra overhead. - * - * @param msg Message to finalize - * @param system_id Id of the sending (this) system, 1-127 - * @param length Message length - */ -MAVLINK_HELPER uint16_t mavlink_finalize_message_buffer(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id, - mavlink_status_t* status, uint8_t min_length, uint8_t length, uint8_t crc_extra) -{ - bool mavlink1 = (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) != 0; -#ifndef MAVLINK_NO_SIGN_PACKET - bool signing = (!mavlink1) && status->signing && (status->signing->flags & MAVLINK_SIGNING_FLAG_SIGN_OUTGOING); -#else - bool signing = false; -#endif - uint8_t signature_len = signing? MAVLINK_SIGNATURE_BLOCK_LEN : 0; - uint8_t header_len = MAVLINK_CORE_HEADER_LEN+1; - uint8_t buf[MAVLINK_CORE_HEADER_LEN+1]; - if (mavlink1) { - msg->magic = MAVLINK_STX_MAVLINK1; - header_len = MAVLINK_CORE_HEADER_MAVLINK1_LEN+1; - } else { - msg->magic = MAVLINK_STX; - } - msg->len = mavlink1?min_length:_mav_trim_payload(_MAV_PAYLOAD(msg), length); - msg->sysid = system_id; - msg->compid = component_id; - msg->incompat_flags = 0; - if (signing) { - msg->incompat_flags |= MAVLINK_IFLAG_SIGNED; - } - msg->compat_flags = 0; - msg->seq = status->current_tx_seq; - status->current_tx_seq = status->current_tx_seq + 1; - - // form the header as a byte array for the crc - buf[0] = msg->magic; - buf[1] = msg->len; - if (mavlink1) { - buf[2] = msg->seq; - buf[3] = msg->sysid; - buf[4] = msg->compid; - buf[5] = msg->msgid & 0xFF; - } else { - buf[2] = msg->incompat_flags; - buf[3] = msg->compat_flags; - buf[4] = msg->seq; - buf[5] = msg->sysid; - buf[6] = msg->compid; - buf[7] = msg->msgid & 0xFF; - buf[8] = (msg->msgid >> 8) & 0xFF; - buf[9] = (msg->msgid >> 16) & 0xFF; - } - - uint16_t checksum = crc_calculate(&buf[1], header_len-1); - crc_accumulate_buffer(&checksum, _MAV_PAYLOAD(msg), msg->len); - crc_accumulate(crc_extra, &checksum); - mavlink_ck_a(msg) = (uint8_t)(checksum & 0xFF); - mavlink_ck_b(msg) = (uint8_t)(checksum >> 8); - - msg->checksum = checksum; - -#ifndef MAVLINK_NO_SIGN_PACKET - if (signing) { - mavlink_sign_packet(status->signing, - msg->signature, - (const uint8_t *)buf, header_len, - (const uint8_t *)_MAV_PAYLOAD(msg), msg->len, - (const uint8_t *)_MAV_PAYLOAD(msg)+(uint16_t)msg->len); - } -#endif - - return msg->len + header_len + 2 + signature_len; -} - -MAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id, - uint8_t chan, uint8_t min_length, uint8_t length, uint8_t crc_extra) -{ - mavlink_status_t *status = mavlink_get_channel_status(chan); - return mavlink_finalize_message_buffer(msg, system_id, component_id, status, min_length, length, crc_extra); -} - -/** - * @brief Finalize a MAVLink message with MAVLINK_COMM_0 as default channel - */ -MAVLINK_HELPER uint16_t mavlink_finalize_message(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id, - uint8_t min_length, uint8_t length, uint8_t crc_extra) -{ - return mavlink_finalize_message_chan(msg, system_id, component_id, MAVLINK_COMM_0, min_length, length, crc_extra); -} - -static inline void _mav_parse_error(mavlink_status_t *status) -{ - status->parse_error++; -} - -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS -MAVLINK_HELPER void _mavlink_send_uart(mavlink_channel_t chan, const char *buf, uint16_t len); - -/** - * @brief Finalize a MAVLink message with channel assignment and send - */ -MAVLINK_HELPER void _mav_finalize_message_chan_send(mavlink_channel_t chan, uint32_t msgid, - const char *packet, - uint8_t min_length, uint8_t length, uint8_t crc_extra) -{ - uint16_t checksum; - uint8_t buf[MAVLINK_NUM_HEADER_BYTES]; - uint8_t ck[2]; - mavlink_status_t *status = mavlink_get_channel_status(chan); - uint8_t header_len = MAVLINK_CORE_HEADER_LEN; - uint8_t signature_len = 0; - uint8_t signature[MAVLINK_SIGNATURE_BLOCK_LEN]; - bool mavlink1 = (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) != 0; - bool signing = (!mavlink1) && status->signing && (status->signing->flags & MAVLINK_SIGNING_FLAG_SIGN_OUTGOING); - - if (mavlink1) { - length = min_length; - if (msgid > 255) { - // can't send 16 bit messages - _mav_parse_error(status); - return; - } - header_len = MAVLINK_CORE_HEADER_MAVLINK1_LEN; - buf[0] = MAVLINK_STX_MAVLINK1; - buf[1] = length; - buf[2] = status->current_tx_seq; - buf[3] = mavlink_system.sysid; - buf[4] = mavlink_system.compid; - buf[5] = msgid & 0xFF; - } else { - uint8_t incompat_flags = 0; - if (signing) { - incompat_flags |= MAVLINK_IFLAG_SIGNED; - } - length = _mav_trim_payload(packet, length); - buf[0] = MAVLINK_STX; - buf[1] = length; - buf[2] = incompat_flags; - buf[3] = 0; // compat_flags - buf[4] = status->current_tx_seq; - buf[5] = mavlink_system.sysid; - buf[6] = mavlink_system.compid; - buf[7] = msgid & 0xFF; - buf[8] = (msgid >> 8) & 0xFF; - buf[9] = (msgid >> 16) & 0xFF; - } - status->current_tx_seq++; - checksum = crc_calculate((const uint8_t*)&buf[1], header_len); - crc_accumulate_buffer(&checksum, packet, length); - crc_accumulate(crc_extra, &checksum); - ck[0] = (uint8_t)(checksum & 0xFF); - ck[1] = (uint8_t)(checksum >> 8); - -#ifndef MAVLINK_NO_SIGN_PACKET - if (signing) { - // possibly add a signature - signature_len = mavlink_sign_packet(status->signing, signature, buf, header_len+1, - (const uint8_t *)packet, length, ck); - } -#endif - - MAVLINK_START_UART_SEND(chan, header_len + 3 + (uint16_t)length + (uint16_t)signature_len); - _mavlink_send_uart(chan, (const char *)buf, header_len+1); - _mavlink_send_uart(chan, packet, length); - _mavlink_send_uart(chan, (const char *)ck, 2); - if (signature_len != 0) { - _mavlink_send_uart(chan, (const char *)signature, signature_len); - } - MAVLINK_END_UART_SEND(chan, header_len + 3 + (uint16_t)length + (uint16_t)signature_len); -} - -/** - * @brief re-send a message over a uart channel - * this is more stack efficient than re-marshalling the message - * If the message is signed then the original signature is also sent - */ -MAVLINK_HELPER void _mavlink_resend_uart(mavlink_channel_t chan, const mavlink_message_t *msg) -{ - uint8_t ck[2]; - - ck[0] = (uint8_t)(msg->checksum & 0xFF); - ck[1] = (uint8_t)(msg->checksum >> 8); - // XXX use the right sequence here - - uint8_t header_len; - uint8_t signature_len; - - if (msg->magic == MAVLINK_STX_MAVLINK1) { - header_len = MAVLINK_CORE_HEADER_MAVLINK1_LEN + 1; - signature_len = 0; - MAVLINK_START_UART_SEND(chan, header_len + msg->len + 2 + signature_len); - // we can't send the structure directly as it has extra mavlink2 elements in it - uint8_t buf[MAVLINK_CORE_HEADER_MAVLINK1_LEN + 1]; - buf[0] = msg->magic; - buf[1] = msg->len; - buf[2] = msg->seq; - buf[3] = msg->sysid; - buf[4] = msg->compid; - buf[5] = msg->msgid & 0xFF; - _mavlink_send_uart(chan, (const char*)buf, header_len); - } else { - header_len = MAVLINK_CORE_HEADER_LEN + 1; - signature_len = (msg->incompat_flags & MAVLINK_IFLAG_SIGNED)?MAVLINK_SIGNATURE_BLOCK_LEN:0; - MAVLINK_START_UART_SEND(chan, header_len + msg->len + 2 + signature_len); - uint8_t buf[MAVLINK_CORE_HEADER_LEN + 1]; - buf[0] = msg->magic; - buf[1] = msg->len; - buf[2] = msg->incompat_flags; - buf[3] = msg->compat_flags; - buf[4] = msg->seq; - buf[5] = msg->sysid; - buf[6] = msg->compid; - buf[7] = msg->msgid & 0xFF; - buf[8] = (msg->msgid >> 8) & 0xFF; - buf[9] = (msg->msgid >> 16) & 0xFF; - _mavlink_send_uart(chan, (const char *)buf, header_len); - } - _mavlink_send_uart(chan, _MAV_PAYLOAD(msg), msg->len); - _mavlink_send_uart(chan, (const char *)ck, 2); - if (signature_len != 0) { - _mavlink_send_uart(chan, (const char *)msg->signature, MAVLINK_SIGNATURE_BLOCK_LEN); - } - MAVLINK_END_UART_SEND(chan, header_len + msg->len + 2 + signature_len); -} -#endif // MAVLINK_USE_CONVENIENCE_FUNCTIONS - -/** - * @brief Pack a message to send it over a serial byte stream - */ -MAVLINK_HELPER uint16_t mavlink_msg_to_send_buffer(uint8_t *buf, const mavlink_message_t *msg) -{ - uint8_t signature_len, header_len; - uint8_t *ck; - uint8_t length = msg->len; - - if (msg->magic == MAVLINK_STX_MAVLINK1) { - signature_len = 0; - header_len = MAVLINK_CORE_HEADER_MAVLINK1_LEN; - buf[0] = msg->magic; - buf[1] = length; - buf[2] = msg->seq; - buf[3] = msg->sysid; - buf[4] = msg->compid; - buf[5] = msg->msgid & 0xFF; - memcpy(&buf[6], _MAV_PAYLOAD(msg), msg->len); - ck = buf + header_len + 1 + (uint16_t)msg->len; - } else { - length = _mav_trim_payload(_MAV_PAYLOAD(msg), length); - header_len = MAVLINK_CORE_HEADER_LEN; - buf[0] = msg->magic; - buf[1] = length; - buf[2] = msg->incompat_flags; - buf[3] = msg->compat_flags; - buf[4] = msg->seq; - buf[5] = msg->sysid; - buf[6] = msg->compid; - buf[7] = msg->msgid & 0xFF; - buf[8] = (msg->msgid >> 8) & 0xFF; - buf[9] = (msg->msgid >> 16) & 0xFF; - memcpy(&buf[10], _MAV_PAYLOAD(msg), length); - ck = buf + header_len + 1 + (uint16_t)length; - signature_len = (msg->incompat_flags & MAVLINK_IFLAG_SIGNED)?MAVLINK_SIGNATURE_BLOCK_LEN:0; - } - ck[0] = (uint8_t)(msg->checksum & 0xFF); - ck[1] = (uint8_t)(msg->checksum >> 8); - if (signature_len > 0) { - memcpy(&ck[2], msg->signature, signature_len); - } - - return header_len + 1 + 2 + (uint16_t)length + (uint16_t)signature_len; -} - -union __mavlink_bitfield { - uint8_t uint8; - int8_t int8; - uint16_t uint16; - int16_t int16; - uint32_t uint32; - int32_t int32; -}; - - -MAVLINK_HELPER void mavlink_start_checksum(mavlink_message_t* msg) -{ - uint16_t crcTmp = 0; - crc_init(&crcTmp); - msg->checksum = crcTmp; -} - -MAVLINK_HELPER void mavlink_update_checksum(mavlink_message_t* msg, uint8_t c) -{ - uint16_t checksum = msg->checksum; - crc_accumulate(c, &checksum); - msg->checksum = checksum; -} - -/* - return the crc_entry value for a msgid -*/ -#ifndef MAVLINK_GET_MSG_ENTRY -MAVLINK_HELPER const mavlink_msg_entry_t *mavlink_get_msg_entry(uint32_t msgid) -{ - static const mavlink_msg_entry_t mavlink_message_crcs[] = MAVLINK_MESSAGE_CRCS; - /* - use a bisection search to find the right entry. A perfect hash may be better - Note that this assumes the table is sorted by msgid - */ - uint32_t low=0, high=sizeof(mavlink_message_crcs)/sizeof(mavlink_message_crcs[0]) - 1; - while (low < high) { - uint32_t mid = (low+1+high)/2; - if (msgid < mavlink_message_crcs[mid].msgid) { - high = mid-1; - continue; - } - if (msgid > mavlink_message_crcs[mid].msgid) { - low = mid; - continue; - } - low = mid; - break; - } - if (mavlink_message_crcs[low].msgid != msgid) { - // msgid is not in the table - return NULL; - } - return &mavlink_message_crcs[low]; -} -#endif // MAVLINK_GET_MSG_ENTRY - -/* - return the crc_extra value for a message -*/ -MAVLINK_HELPER uint8_t mavlink_get_crc_extra(const mavlink_message_t *msg) -{ - const mavlink_msg_entry_t *e = mavlink_get_msg_entry(msg->msgid); - return e?e->crc_extra:0; -} - -/* - return the min message length -*/ -#define MAVLINK_HAVE_MIN_MESSAGE_LENGTH -MAVLINK_HELPER uint8_t mavlink_min_message_length(const mavlink_message_t *msg) -{ - const mavlink_msg_entry_t *e = mavlink_get_msg_entry(msg->msgid); - return e?e->min_msg_len:0; -} - -/* - return the max message length (including extensions) -*/ -#define MAVLINK_HAVE_MAX_MESSAGE_LENGTH -MAVLINK_HELPER uint8_t mavlink_max_message_length(const mavlink_message_t *msg) -{ - const mavlink_msg_entry_t *e = mavlink_get_msg_entry(msg->msgid); - return e?e->max_msg_len:0; -} - -/** - * This is a variant of mavlink_frame_char() but with caller supplied - * parsing buffers. It is useful when you want to create a MAVLink - * parser in a library that doesn't use any global variables - * - * @param rxmsg parsing message buffer - * @param status parsing status buffer - * @param c The char to parse - * - * @param r_message NULL if no message could be decoded, otherwise the message data - * @param r_mavlink_status if a message was decoded, this is filled with the channel's stats - * @return 0 if no message could be decoded, 1 on good message and CRC, 2 on bad CRC - * - */ -MAVLINK_HELPER uint8_t mavlink_frame_char_buffer(mavlink_message_t* rxmsg, - mavlink_status_t* status, - uint8_t c, - mavlink_message_t* r_message, - mavlink_status_t* r_mavlink_status) -{ - - status->msg_received = MAVLINK_FRAMING_INCOMPLETE; - - switch (status->parse_state) - { - case MAVLINK_PARSE_STATE_UNINIT: - case MAVLINK_PARSE_STATE_IDLE: - if (c == MAVLINK_STX) - { - status->parse_state = MAVLINK_PARSE_STATE_GOT_STX; - rxmsg->len = 0; - rxmsg->magic = c; - status->flags &= ~MAVLINK_STATUS_FLAG_IN_MAVLINK1; - mavlink_start_checksum(rxmsg); - } else if (c == MAVLINK_STX_MAVLINK1) - { - status->parse_state = MAVLINK_PARSE_STATE_GOT_STX; - rxmsg->len = 0; - rxmsg->magic = c; - status->flags |= MAVLINK_STATUS_FLAG_IN_MAVLINK1; - mavlink_start_checksum(rxmsg); - } - break; - - case MAVLINK_PARSE_STATE_GOT_STX: - if (status->msg_received -/* Support shorter buffers than the - default maximum packet size */ -#if (MAVLINK_MAX_PAYLOAD_LEN < 255) - || c > MAVLINK_MAX_PAYLOAD_LEN -#endif - ) - { - status->buffer_overrun++; - _mav_parse_error(status); - status->msg_received = 0; - status->parse_state = MAVLINK_PARSE_STATE_IDLE; - } - else - { - // NOT counting STX, LENGTH, SEQ, SYSID, COMPID, MSGID, CRC1 and CRC2 - rxmsg->len = c; - status->packet_idx = 0; - mavlink_update_checksum(rxmsg, c); - if (status->flags & MAVLINK_STATUS_FLAG_IN_MAVLINK1) { - rxmsg->incompat_flags = 0; - rxmsg->compat_flags = 0; - status->parse_state = MAVLINK_PARSE_STATE_GOT_COMPAT_FLAGS; - } else { - status->parse_state = MAVLINK_PARSE_STATE_GOT_LENGTH; - } - } - break; - - case MAVLINK_PARSE_STATE_GOT_LENGTH: - rxmsg->incompat_flags = c; - if ((rxmsg->incompat_flags & ~MAVLINK_IFLAG_MASK) != 0) { - // message includes an incompatible feature flag - _mav_parse_error(status); - status->msg_received = 0; - status->parse_state = MAVLINK_PARSE_STATE_IDLE; - break; - } - mavlink_update_checksum(rxmsg, c); - status->parse_state = MAVLINK_PARSE_STATE_GOT_INCOMPAT_FLAGS; - break; - - case MAVLINK_PARSE_STATE_GOT_INCOMPAT_FLAGS: - rxmsg->compat_flags = c; - mavlink_update_checksum(rxmsg, c); - status->parse_state = MAVLINK_PARSE_STATE_GOT_COMPAT_FLAGS; - break; - - case MAVLINK_PARSE_STATE_GOT_COMPAT_FLAGS: - rxmsg->seq = c; - mavlink_update_checksum(rxmsg, c); - status->parse_state = MAVLINK_PARSE_STATE_GOT_SEQ; - break; - - case MAVLINK_PARSE_STATE_GOT_SEQ: - rxmsg->sysid = c; - mavlink_update_checksum(rxmsg, c); - status->parse_state = MAVLINK_PARSE_STATE_GOT_SYSID; - break; - - case MAVLINK_PARSE_STATE_GOT_SYSID: - rxmsg->compid = c; - mavlink_update_checksum(rxmsg, c); - status->parse_state = MAVLINK_PARSE_STATE_GOT_COMPID; - break; - - case MAVLINK_PARSE_STATE_GOT_COMPID: - rxmsg->msgid = c; - mavlink_update_checksum(rxmsg, c); - if (status->flags & MAVLINK_STATUS_FLAG_IN_MAVLINK1) { - if(rxmsg->len > 0) { - status->parse_state = MAVLINK_PARSE_STATE_GOT_MSGID3; - } else { - status->parse_state = MAVLINK_PARSE_STATE_GOT_PAYLOAD; - } -#ifdef MAVLINK_CHECK_MESSAGE_LENGTH - if (rxmsg->len < mavlink_min_message_length(rxmsg) || - rxmsg->len > mavlink_max_message_length(rxmsg)) { - _mav_parse_error(status); - status->parse_state = MAVLINK_PARSE_STATE_IDLE; - break; - } -#endif - } else { - status->parse_state = MAVLINK_PARSE_STATE_GOT_MSGID1; - } - break; - - case MAVLINK_PARSE_STATE_GOT_MSGID1: - rxmsg->msgid |= c<<8; - mavlink_update_checksum(rxmsg, c); - status->parse_state = MAVLINK_PARSE_STATE_GOT_MSGID2; - break; - - case MAVLINK_PARSE_STATE_GOT_MSGID2: - rxmsg->msgid |= ((uint32_t)c)<<16; - mavlink_update_checksum(rxmsg, c); - if(rxmsg->len > 0){ - status->parse_state = MAVLINK_PARSE_STATE_GOT_MSGID3; - } else { - status->parse_state = MAVLINK_PARSE_STATE_GOT_PAYLOAD; - } -#ifdef MAVLINK_CHECK_MESSAGE_LENGTH - if (rxmsg->len < mavlink_min_message_length(rxmsg) || - rxmsg->len > mavlink_max_message_length(rxmsg)) - { - _mav_parse_error(status); - status->parse_state = MAVLINK_PARSE_STATE_IDLE; - break; - } -#endif - break; - - case MAVLINK_PARSE_STATE_GOT_MSGID3: - _MAV_PAYLOAD_NON_CONST(rxmsg)[status->packet_idx++] = (char)c; - mavlink_update_checksum(rxmsg, c); - if (status->packet_idx == rxmsg->len) - { - status->parse_state = MAVLINK_PARSE_STATE_GOT_PAYLOAD; - } - break; - - case MAVLINK_PARSE_STATE_GOT_PAYLOAD: { - const mavlink_msg_entry_t *e = mavlink_get_msg_entry(rxmsg->msgid); - uint8_t crc_extra = e?e->crc_extra:0; - mavlink_update_checksum(rxmsg, crc_extra); - if (c != (rxmsg->checksum & 0xFF)) { - status->parse_state = MAVLINK_PARSE_STATE_GOT_BAD_CRC1; - } else { - status->parse_state = MAVLINK_PARSE_STATE_GOT_CRC1; - } - rxmsg->ck[0] = c; - - // zero-fill the packet to cope with short incoming packets - if (e && status->packet_idx < e->max_msg_len) { - memset(&_MAV_PAYLOAD_NON_CONST(rxmsg)[status->packet_idx], 0, e->max_msg_len - status->packet_idx); - } - break; - } - - case MAVLINK_PARSE_STATE_GOT_CRC1: - case MAVLINK_PARSE_STATE_GOT_BAD_CRC1: - if (status->parse_state == MAVLINK_PARSE_STATE_GOT_BAD_CRC1 || c != (rxmsg->checksum >> 8)) { - // got a bad CRC message - status->msg_received = MAVLINK_FRAMING_BAD_CRC; - } else { - // Successfully got message - status->msg_received = MAVLINK_FRAMING_OK; - } - rxmsg->ck[1] = c; - - if (rxmsg->incompat_flags & MAVLINK_IFLAG_SIGNED) { - status->parse_state = MAVLINK_PARSE_STATE_SIGNATURE_WAIT; - status->signature_wait = MAVLINK_SIGNATURE_BLOCK_LEN; - - // If the CRC is already wrong, don't overwrite msg_received, - // otherwise we can end up with garbage flagged as valid. - if (status->msg_received != MAVLINK_FRAMING_BAD_CRC) { - status->msg_received = MAVLINK_FRAMING_INCOMPLETE; - } - } else { - if (status->signing && - (status->signing->accept_unsigned_callback == NULL || - !status->signing->accept_unsigned_callback(status, rxmsg->msgid))) { - - // If the CRC is already wrong, don't overwrite msg_received. - if (status->msg_received != MAVLINK_FRAMING_BAD_CRC) { - status->msg_received = MAVLINK_FRAMING_BAD_SIGNATURE; - } - } - status->parse_state = MAVLINK_PARSE_STATE_IDLE; - if (r_message != NULL) { - memcpy(r_message, rxmsg, sizeof(mavlink_message_t)); - } - } - break; - case MAVLINK_PARSE_STATE_SIGNATURE_WAIT: - rxmsg->signature[MAVLINK_SIGNATURE_BLOCK_LEN-status->signature_wait] = c; - status->signature_wait--; - if (status->signature_wait == 0) { - // we have the whole signature, check it is OK -#ifndef MAVLINK_NO_SIGNATURE_CHECK - bool sig_ok = mavlink_signature_check(status->signing, status->signing_streams, rxmsg); -#else - bool sig_ok = true; -#endif - if (!sig_ok && - (status->signing->accept_unsigned_callback && - status->signing->accept_unsigned_callback(status, rxmsg->msgid))) { - // accepted via application level override - sig_ok = true; - } - if (sig_ok) { - status->msg_received = MAVLINK_FRAMING_OK; - } else { - status->msg_received = MAVLINK_FRAMING_BAD_SIGNATURE; - } - status->parse_state = MAVLINK_PARSE_STATE_IDLE; - if (r_message !=NULL) { - memcpy(r_message, rxmsg, sizeof(mavlink_message_t)); - } - } - break; - } - - // If a message has been successfully decoded, check index - if (status->msg_received == MAVLINK_FRAMING_OK) - { - //while(status->current_seq != rxmsg->seq) - //{ - // status->packet_rx_drop_count++; - // status->current_seq++; - //} - status->current_rx_seq = rxmsg->seq; - // Initial condition: If no packet has been received so far, drop count is undefined - if (status->packet_rx_success_count == 0) status->packet_rx_drop_count = 0; - // Count this packet as received - status->packet_rx_success_count++; - } - - if (r_message != NULL) { - r_message->len = rxmsg->len; // Provide visibility on how far we are into current msg - } - if (r_mavlink_status != NULL) { - r_mavlink_status->parse_state = status->parse_state; - r_mavlink_status->packet_idx = status->packet_idx; - r_mavlink_status->current_rx_seq = status->current_rx_seq+1; - r_mavlink_status->packet_rx_success_count = status->packet_rx_success_count; - r_mavlink_status->packet_rx_drop_count = status->parse_error; - r_mavlink_status->flags = status->flags; - } - status->parse_error = 0; - - if (status->msg_received == MAVLINK_FRAMING_BAD_CRC) { - /* - the CRC came out wrong. We now need to overwrite the - msg CRC with the one on the wire so that if the - caller decides to forward the message anyway that - mavlink_msg_to_send_buffer() won't overwrite the - checksum - */ - if (r_message != NULL) { - r_message->checksum = rxmsg->ck[0] | (rxmsg->ck[1]<<8); - } - } - - return status->msg_received; -} - -/** - * This is a convenience function which handles the complete MAVLink parsing. - * the function will parse one byte at a time and return the complete packet once - * it could be successfully decoded. This function will return 0, 1 or - * 2 (MAVLINK_FRAMING_INCOMPLETE, MAVLINK_FRAMING_OK or MAVLINK_FRAMING_BAD_CRC) - * - * Messages are parsed into an internal buffer (one for each channel). When a complete - * message is received it is copies into *r_message and the channel's status is - * copied into *r_mavlink_status. - * - * @param chan ID of the channel to be parsed. - * A channel is not a physical message channel like a serial port, but a logical partition of - * the communication streams. COMM_NB is the limit for the number of channels - * on MCU (e.g. ARM7), while COMM_NB_HIGH is the limit for the number of channels in Linux/Windows - * @param c The char to parse - * - * @param r_message NULL if no message could be decoded, otherwise the message data - * @param r_mavlink_status if a message was decoded, this is filled with the channel's stats - * @return 0 if no message could be decoded, 1 on good message and CRC, 2 on bad CRC - * - * A typical use scenario of this function call is: - * - * @code - * #include - * - * mavlink_status_t status; - * mavlink_message_t msg; - * int chan = 0; - * - * - * while(serial.bytesAvailable > 0) - * { - * uint8_t byte = serial.getNextByte(); - * if (mavlink_frame_char(chan, byte, &msg, &status) != MAVLINK_FRAMING_INCOMPLETE) - * { - * printf("Received message with ID %d, sequence: %d from component %d of system %d", msg.msgid, msg.seq, msg.compid, msg.sysid); - * } - * } - * - * - * @endcode - */ -MAVLINK_HELPER uint8_t mavlink_frame_char(uint8_t chan, uint8_t c, mavlink_message_t* r_message, mavlink_status_t* r_mavlink_status) -{ - return mavlink_frame_char_buffer(mavlink_get_channel_buffer(chan), - mavlink_get_channel_status(chan), - c, - r_message, - r_mavlink_status); -} - -/** - * Set the protocol version - */ -MAVLINK_HELPER void mavlink_set_proto_version(uint8_t chan, unsigned int version) -{ - mavlink_status_t *status = mavlink_get_channel_status(chan); - if (version > 1) { - status->flags &= ~(MAVLINK_STATUS_FLAG_OUT_MAVLINK1); - } else { - status->flags |= MAVLINK_STATUS_FLAG_OUT_MAVLINK1; - } -} - -/** - * Get the protocol version - * - * @return 1 for v1, 2 for v2 - */ -MAVLINK_HELPER unsigned int mavlink_get_proto_version(uint8_t chan) -{ - mavlink_status_t *status = mavlink_get_channel_status(chan); - if ((status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) > 0) { - return 1; - } else { - return 2; - } -} - -/** - * This is a convenience function which handles the complete MAVLink parsing. - * the function will parse one byte at a time and return the complete packet once - * it could be successfully decoded. This function will return 0 or 1. - * - * Messages are parsed into an internal buffer (one for each channel). When a complete - * message is received it is copies into *r_message and the channel's status is - * copied into *r_mavlink_status. - * - * @param chan ID of the channel to be parsed. - * A channel is not a physical message channel like a serial port, but a logical partition of - * the communication streams. COMM_NB is the limit for the number of channels - * on MCU (e.g. ARM7), while COMM_NB_HIGH is the limit for the number of channels in Linux/Windows - * @param c The char to parse - * - * @param r_message NULL if no message could be decoded, otherwise the message data - * @param r_mavlink_status if a message was decoded, this is filled with the channel's stats - * @return 0 if no message could be decoded or bad CRC, 1 on good message and CRC - * - * A typical use scenario of this function call is: - * - * @code - * #include - * - * mavlink_status_t status; - * mavlink_message_t msg; - * int chan = 0; - * - * - * while(serial.bytesAvailable > 0) - * { - * uint8_t byte = serial.getNextByte(); - * if (mavlink_parse_char(chan, byte, &msg, &status)) - * { - * printf("Received message with ID %d, sequence: %d from component %d of system %d", msg.msgid, msg.seq, msg.compid, msg.sysid); - * } - * } - * - * - * @endcode - */ -MAVLINK_HELPER uint8_t mavlink_parse_char(uint8_t chan, uint8_t c, mavlink_message_t* r_message, mavlink_status_t* r_mavlink_status) -{ - uint8_t msg_received = mavlink_frame_char(chan, c, r_message, r_mavlink_status); - if (msg_received == MAVLINK_FRAMING_BAD_CRC || - msg_received == MAVLINK_FRAMING_BAD_SIGNATURE) { - // we got a bad CRC. Treat as a parse failure - mavlink_message_t* rxmsg = mavlink_get_channel_buffer(chan); - mavlink_status_t* status = mavlink_get_channel_status(chan); - _mav_parse_error(status); - status->msg_received = MAVLINK_FRAMING_INCOMPLETE; - status->parse_state = MAVLINK_PARSE_STATE_IDLE; - if (c == MAVLINK_STX) - { - status->parse_state = MAVLINK_PARSE_STATE_GOT_STX; - rxmsg->len = 0; - mavlink_start_checksum(rxmsg); - } - return 0; - } - return msg_received; -} - -/** - * @brief Put a bitfield of length 1-32 bit into the buffer - * - * @param b the value to add, will be encoded in the bitfield - * @param bits number of bits to use to encode b, e.g. 1 for boolean, 2, 3, etc. - * @param packet_index the position in the packet (the index of the first byte to use) - * @param bit_index the position in the byte (the index of the first bit to use) - * @param buffer packet buffer to write into - * @return new position of the last used byte in the buffer - */ -MAVLINK_HELPER uint8_t put_bitfield_n_by_index(int32_t b, uint8_t bits, uint8_t packet_index, uint8_t bit_index, uint8_t* r_bit_index, uint8_t* buffer) -{ - uint16_t bits_remain = bits; - // Transform number into network order - int32_t v; - uint8_t i_bit_index, i_byte_index, curr_bits_n; -#if MAVLINK_NEED_BYTE_SWAP - union { - int32_t i; - uint8_t b[4]; - } bin, bout; - bin.i = b; - bout.b[0] = bin.b[3]; - bout.b[1] = bin.b[2]; - bout.b[2] = bin.b[1]; - bout.b[3] = bin.b[0]; - v = bout.i; -#else - v = b; -#endif - - // buffer in - // 01100000 01000000 00000000 11110001 - // buffer out - // 11110001 00000000 01000000 01100000 - - // Existing partly filled byte (four free slots) - // 0111xxxx - - // Mask n free bits - // 00001111 = 2^0 + 2^1 + 2^2 + 2^3 = 2^n - 1 - // = ((uint32_t)(1 << n)) - 1; // = 2^n - 1 - - // Shift n bits into the right position - // out = in >> n; - - // Mask and shift bytes - i_bit_index = bit_index; - i_byte_index = packet_index; - if (bit_index > 0) - { - // If bits were available at start, they were available - // in the byte before the current index - i_byte_index--; - } - - // While bits have not been packed yet - while (bits_remain > 0) - { - // Bits still have to be packed - // there can be more than 8 bits, so - // we might have to pack them into more than one byte - - // First pack everything we can into the current 'open' byte - //curr_bits_n = bits_remain << 3; // Equals bits_remain mod 8 - //FIXME - if (bits_remain <= (uint8_t)(8 - i_bit_index)) - { - // Enough space - curr_bits_n = (uint8_t)bits_remain; - } - else - { - curr_bits_n = (8 - i_bit_index); - } - - // Pack these n bits into the current byte - // Mask out whatever was at that position with ones (xxx11111) - buffer[i_byte_index] &= (0xFF >> (8 - curr_bits_n)); - // Put content to this position, by masking out the non-used part - buffer[i_byte_index] |= ((0x00 << curr_bits_n) & v); - - // Increment the bit index - i_bit_index += curr_bits_n; - - // Now proceed to the next byte, if necessary - bits_remain -= curr_bits_n; - if (bits_remain > 0) - { - // Offer another 8 bits / one byte - i_byte_index++; - i_bit_index = 0; - } - } - - *r_bit_index = i_bit_index; - // If a partly filled byte is present, mark this as consumed - if (i_bit_index != 7) i_byte_index++; - return i_byte_index - packet_index; -} - -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -// To make MAVLink work on your MCU, define comm_send_ch() if you wish -// to send 1 byte at a time, or MAVLINK_SEND_UART_BYTES() to send a -// whole packet at a time - -/* - -#include "mavlink_types.h" - -void comm_send_ch(mavlink_channel_t chan, uint8_t ch) -{ - if (chan == MAVLINK_COMM_0) - { - uart0_transmit(ch); - } - if (chan == MAVLINK_COMM_1) - { - uart1_transmit(ch); - } -} - */ - -MAVLINK_HELPER void _mavlink_send_uart(mavlink_channel_t chan, const char *buf, uint16_t len) -{ -#ifdef MAVLINK_SEND_UART_BYTES - /* this is the more efficient approach, if the platform - defines it */ - MAVLINK_SEND_UART_BYTES(chan, (const uint8_t *)buf, len); -#else - /* fallback to one byte at a time */ - uint16_t i; - for (i = 0; i < len; i++) { - comm_send_ch(chan, (uint8_t)buf[i]); - } -#endif -} -#endif // MAVLINK_USE_CONVENIENCE_FUNCTIONS - -#ifdef MAVLINK_USE_CXX_NAMESPACE -} // namespace mavlink -#endif diff --git a/TelemetryManager/Inc/official_mavlink_2_library/mavlink_sha256.h b/TelemetryManager/Inc/official_mavlink_2_library/mavlink_sha256.h deleted file mode 100644 index 7accd035..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/mavlink_sha256.h +++ /dev/null @@ -1,235 +0,0 @@ -#pragma once - -/* - sha-256 implementation for MAVLink based on Heimdal sources, with - modifications to suit mavlink headers - */ -/* - * Copyright (c) 1995 - 2001 Kungliga Tekniska Högskolan - * (Royal Institute of Technology, Stockholm, Sweden). - * All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in the - * documentation and/or other materials provided with the distribution. - * - * 3. Neither the name of the Institute nor the names of its contributors - * may be used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE INSTITUTE AND CONTRIBUTORS ``AS IS'' AND - * ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE INSTITUTE OR CONTRIBUTORS BE LIABLE - * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL - * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS - * OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) - * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY - * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF - * SUCH DAMAGE. - */ - -/* - allow implementation to provide their own sha256 with the same API -*/ -#ifndef HAVE_MAVLINK_SHA256 - -#ifdef MAVLINK_USE_CXX_NAMESPACE -namespace mavlink { -#endif - -#ifndef MAVLINK_HELPER -#define MAVLINK_HELPER -#endif - -typedef struct { - uint32_t sz[2]; - uint32_t counter[8]; - union { - unsigned char save_bytes[64]; - uint32_t save_u32[16]; - } u; -} mavlink_sha256_ctx; - -#define Ch(x,y,z) (((x) & (y)) ^ ((~(x)) & (z))) -#define Maj(x,y,z) (((x) & (y)) ^ ((x) & (z)) ^ ((y) & (z))) - -#define ROTR(x,n) (((x)>>(n)) | ((x) << (32 - (n)))) - -#define Sigma0(x) (ROTR(x,2) ^ ROTR(x,13) ^ ROTR(x,22)) -#define Sigma1(x) (ROTR(x,6) ^ ROTR(x,11) ^ ROTR(x,25)) -#define sigma0(x) (ROTR(x,7) ^ ROTR(x,18) ^ ((x)>>3)) -#define sigma1(x) (ROTR(x,17) ^ ROTR(x,19) ^ ((x)>>10)) - -static const uint32_t mavlink_sha256_constant_256[64] = { - 0x428a2f98, 0x71374491, 0xb5c0fbcf, 0xe9b5dba5, - 0x3956c25b, 0x59f111f1, 0x923f82a4, 0xab1c5ed5, - 0xd807aa98, 0x12835b01, 0x243185be, 0x550c7dc3, - 0x72be5d74, 0x80deb1fe, 0x9bdc06a7, 0xc19bf174, - 0xe49b69c1, 0xefbe4786, 0x0fc19dc6, 0x240ca1cc, - 0x2de92c6f, 0x4a7484aa, 0x5cb0a9dc, 0x76f988da, - 0x983e5152, 0xa831c66d, 0xb00327c8, 0xbf597fc7, - 0xc6e00bf3, 0xd5a79147, 0x06ca6351, 0x14292967, - 0x27b70a85, 0x2e1b2138, 0x4d2c6dfc, 0x53380d13, - 0x650a7354, 0x766a0abb, 0x81c2c92e, 0x92722c85, - 0xa2bfe8a1, 0xa81a664b, 0xc24b8b70, 0xc76c51a3, - 0xd192e819, 0xd6990624, 0xf40e3585, 0x106aa070, - 0x19a4c116, 0x1e376c08, 0x2748774c, 0x34b0bcb5, - 0x391c0cb3, 0x4ed8aa4a, 0x5b9cca4f, 0x682e6ff3, - 0x748f82ee, 0x78a5636f, 0x84c87814, 0x8cc70208, - 0x90befffa, 0xa4506ceb, 0xbef9a3f7, 0xc67178f2 -}; - -MAVLINK_HELPER void mavlink_sha256_init(mavlink_sha256_ctx *m) -{ - m->sz[0] = 0; - m->sz[1] = 0; - m->counter[0] = 0x6a09e667; - m->counter[1] = 0xbb67ae85; - m->counter[2] = 0x3c6ef372; - m->counter[3] = 0xa54ff53a; - m->counter[4] = 0x510e527f; - m->counter[5] = 0x9b05688c; - m->counter[6] = 0x1f83d9ab; - m->counter[7] = 0x5be0cd19; -} - -static inline void mavlink_sha256_calc(mavlink_sha256_ctx *m, uint32_t *in) -{ - uint32_t AA, BB, CC, DD, EE, FF, GG, HH; - uint32_t data[64]; - int i; - - AA = m->counter[0]; - BB = m->counter[1]; - CC = m->counter[2]; - DD = m->counter[3]; - EE = m->counter[4]; - FF = m->counter[5]; - GG = m->counter[6]; - HH = m->counter[7]; - - for (i = 0; i < 16; ++i) - data[i] = in[i]; - for (i = 16; i < 64; ++i) - data[i] = sigma1(data[i-2]) + data[i-7] + - sigma0(data[i-15]) + data[i - 16]; - - for (i = 0; i < 64; i++) { - uint32_t T1, T2; - - T1 = HH + Sigma1(EE) + Ch(EE, FF, GG) + mavlink_sha256_constant_256[i] + data[i]; - T2 = Sigma0(AA) + Maj(AA,BB,CC); - - HH = GG; - GG = FF; - FF = EE; - EE = DD + T1; - DD = CC; - CC = BB; - BB = AA; - AA = T1 + T2; - } - - m->counter[0] += AA; - m->counter[1] += BB; - m->counter[2] += CC; - m->counter[3] += DD; - m->counter[4] += EE; - m->counter[5] += FF; - m->counter[6] += GG; - m->counter[7] += HH; -} - -MAVLINK_HELPER void mavlink_sha256_update(mavlink_sha256_ctx *m, const void *v, uint32_t len) -{ - const unsigned char *p = (const unsigned char *)v; - uint32_t old_sz = m->sz[0]; - uint32_t offset; - - m->sz[0] += len * 8; - if (m->sz[0] < old_sz) - ++m->sz[1]; - offset = (old_sz / 8) % 64; - while(len > 0){ - uint32_t l = 64 - offset; - if (len < l) { - l = len; - } - memcpy(m->u.save_bytes + offset, p, l); - offset += l; - p += l; - len -= l; - if(offset == 64){ - int i; - uint32_t current[16]; - const uint32_t *u = m->u.save_u32; - for (i = 0; i < 16; i++){ - const uint8_t *p1 = (const uint8_t *)&u[i]; - uint8_t *p2 = (uint8_t *)¤t[i]; - p2[0] = p1[3]; - p2[1] = p1[2]; - p2[2] = p1[1]; - p2[3] = p1[0]; - } - mavlink_sha256_calc(m, current); - offset = 0; - } - } -} - -/* - get first 48 bits of final sha256 hash - */ -MAVLINK_HELPER void mavlink_sha256_final_48(mavlink_sha256_ctx *m, uint8_t result[6]) -{ - unsigned char zeros[72]; - unsigned offset = (m->sz[0] / 8) % 64; - unsigned int dstart = (120 - offset - 1) % 64 + 1; - uint8_t *p = (uint8_t *)&m->counter[0]; - - *zeros = 0x80; - memset (zeros + 1, 0, sizeof(zeros) - 1); - zeros[dstart+7] = (m->sz[0] >> 0) & 0xff; - zeros[dstart+6] = (m->sz[0] >> 8) & 0xff; - zeros[dstart+5] = (m->sz[0] >> 16) & 0xff; - zeros[dstart+4] = (m->sz[0] >> 24) & 0xff; - zeros[dstart+3] = (m->sz[1] >> 0) & 0xff; - zeros[dstart+2] = (m->sz[1] >> 8) & 0xff; - zeros[dstart+1] = (m->sz[1] >> 16) & 0xff; - zeros[dstart+0] = (m->sz[1] >> 24) & 0xff; - - mavlink_sha256_update(m, zeros, dstart + 8); - - // this ordering makes the result consistent with taking the first - // 6 bytes of more conventional sha256 functions. It assumes - // little-endian ordering of m->counter - result[0] = p[3]; - result[1] = p[2]; - result[2] = p[1]; - result[3] = p[0]; - result[4] = p[7]; - result[5] = p[6]; -} - -// prevent conflicts with users of the header -#undef Ch -#undef ROTR -#undef Sigma0 -#undef Sigma1 -#undef sigma0 -#undef sigma1 - -#ifdef MAVLINK_USE_CXX_NAMESPACE -} // namespace mavlink -#endif - -#endif // HAVE_MAVLINK_SHA256 diff --git a/TelemetryManager/Inc/official_mavlink_2_library/mavlink_types.h b/TelemetryManager/Inc/official_mavlink_2_library/mavlink_types.h deleted file mode 100644 index b1e6d9e3..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/mavlink_types.h +++ /dev/null @@ -1,312 +0,0 @@ -#pragma once - -// Visual Studio versions before 2010 don't have stdint.h, so we just error out. -#if (defined _MSC_VER) && (_MSC_VER < 1600) -#error "The C-MAVLink implementation requires Visual Studio 2010 or greater" -#endif - -#include -#include - -#ifdef MAVLINK_USE_CXX_NAMESPACE -namespace mavlink { -#endif - -// Macro to define packed structures -#ifdef __GNUC__ - #define MAVPACKED( __Declaration__ ) __Declaration__ __attribute__((packed)) -#else - #define MAVPACKED( __Declaration__ ) __pragma( pack(push, 1) ) __Declaration__ __pragma( pack(pop) ) -#endif - -#ifndef MAVLINK_MAX_PAYLOAD_LEN -// it is possible to override this, but be careful! -#define MAVLINK_MAX_PAYLOAD_LEN 255 ///< Maximum payload length -#endif - -#define MAVLINK_CORE_HEADER_LEN 9 ///< Length of core header (of the comm. layer) -#define MAVLINK_CORE_HEADER_MAVLINK1_LEN 5 ///< Length of MAVLink1 core header (of the comm. layer) -#define MAVLINK_NUM_HEADER_BYTES (MAVLINK_CORE_HEADER_LEN + 1) ///< Length of all header bytes, including core and stx -#define MAVLINK_NUM_CHECKSUM_BYTES 2 -#define MAVLINK_NUM_NON_PAYLOAD_BYTES (MAVLINK_NUM_HEADER_BYTES + MAVLINK_NUM_CHECKSUM_BYTES) - -#define MAVLINK_SIGNATURE_BLOCK_LEN 13 - -#define MAVLINK_MAX_PACKET_LEN (MAVLINK_MAX_PAYLOAD_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES + MAVLINK_SIGNATURE_BLOCK_LEN) ///< Maximum packet length - -/** - * Old-style 4 byte param union - * - * This struct is the data format to be used when sending - * parameters. The parameter should be copied to the native - * type (without type conversion) - * and re-instanted on the receiving side using the - * native type as well. - */ -MAVPACKED( -typedef struct param_union { - union { - float param_float; - int32_t param_int32; - uint32_t param_uint32; - int16_t param_int16; - uint16_t param_uint16; - int8_t param_int8; - uint8_t param_uint8; - uint8_t bytes[4]; - }; - uint8_t type; -}) mavlink_param_union_t; - - -/** - * New-style 8 byte param union - * mavlink_param_union_double_t will be 8 bytes long, and treated as needing 8 byte alignment for the purposes of MAVLink 1.0 field ordering. - * The mavlink_param_union_double_t will be treated as a little-endian structure. - * - * If is_double is 1 then the type is a double, and the remaining 63 bits are the double, with the lowest bit of the mantissa zero. - * The intention is that by replacing the is_double bit with 0 the type can be directly used as a double (as the is_double bit corresponds to the - * lowest mantissa bit of a double). If is_double is 0 then mavlink_type gives the type in the union. - * The mavlink_types.h header will also need to have shifts/masks to define the bit boundaries in the above, - * as bitfield ordering isn't consistent between platforms. The above is intended to be for gcc on x86, - * which should be the same as gcc on little-endian arm. When using shifts/masks the value will be treated as a 64 bit unsigned number, - * and the bits pulled out using the shifts/masks. -*/ -MAVPACKED( -typedef struct param_union_extended { - union { - struct { - uint8_t is_double:1; - uint8_t mavlink_type:7; - union { - char c; - uint8_t uint8; - int8_t int8; - uint16_t uint16; - int16_t int16; - uint32_t uint32; - int32_t int32; - float f; - uint8_t align[7]; - }; - }; - uint8_t data[8]; - }; -}) mavlink_param_union_double_t; - -/** - * This structure is required to make the mavlink_send_xxx convenience functions - * work, as it tells the library what the current system and component ID are. - */ -MAVPACKED( -typedef struct __mavlink_system { - uint8_t sysid; ///< Used by the MAVLink message_xx_send() convenience function - uint8_t compid; ///< Used by the MAVLink message_xx_send() convenience function -}) mavlink_system_t; - -MAVPACKED( -typedef struct __mavlink_message { - uint16_t checksum; ///< sent at end of packet - uint8_t magic; ///< protocol magic marker - uint8_t len; ///< Length of payload - uint8_t incompat_flags; ///< flags that must be understood - uint8_t compat_flags; ///< flags that can be ignored if not understood - uint8_t seq; ///< Sequence of packet - uint8_t sysid; ///< ID of message sender system/aircraft - uint8_t compid; ///< ID of the message sender component - uint32_t msgid:24; ///< ID of message in payload - uint64_t payload64[(MAVLINK_MAX_PAYLOAD_LEN+MAVLINK_NUM_CHECKSUM_BYTES+7)/8]; - uint8_t ck[2]; ///< incoming checksum bytes - uint8_t signature[MAVLINK_SIGNATURE_BLOCK_LEN]; -}) mavlink_message_t; - -typedef enum { - MAVLINK_TYPE_CHAR = 0, - MAVLINK_TYPE_UINT8_T = 1, - MAVLINK_TYPE_INT8_T = 2, - MAVLINK_TYPE_UINT16_T = 3, - MAVLINK_TYPE_INT16_T = 4, - MAVLINK_TYPE_UINT32_T = 5, - MAVLINK_TYPE_INT32_T = 6, - MAVLINK_TYPE_UINT64_T = 7, - MAVLINK_TYPE_INT64_T = 8, - MAVLINK_TYPE_FLOAT = 9, - MAVLINK_TYPE_DOUBLE = 10 -} mavlink_message_type_t; - -#define MAVLINK_MAX_FIELDS 64 - -typedef struct __mavlink_field_info { - const char *name; // name of this field - const char *print_format; // printing format hint, or NULL - mavlink_message_type_t type; // type of this field - unsigned int array_length; // if non-zero, field is an array - unsigned int wire_offset; // offset of each field in the payload - unsigned int structure_offset; // offset in a C structure -} mavlink_field_info_t; - -// note that in this structure the order of fields is the order -// in the XML file, not necessary the wire order -typedef struct __mavlink_message_info { - uint32_t msgid; // message ID - const char *name; // name of the message - unsigned num_fields; // how many fields in this message - mavlink_field_info_t fields[MAVLINK_MAX_FIELDS]; // field information -} mavlink_message_info_t; - -#define _MAV_PAYLOAD(msg) ((const char *)(&((msg)->payload64[0]))) -#define _MAV_PAYLOAD_NON_CONST(msg) ((char *)(&((msg)->payload64[0]))) - -// checksum is immediately after the payload bytes -#define mavlink_ck_a(msg) *((msg)->len + (uint8_t *)_MAV_PAYLOAD_NON_CONST(msg)) -#define mavlink_ck_b(msg) *(((msg)->len+(uint16_t)1) + (uint8_t *)_MAV_PAYLOAD_NON_CONST(msg)) - -#ifndef HAVE_MAVLINK_CHANNEL_T -typedef enum { - MAVLINK_COMM_0, - MAVLINK_COMM_1, - MAVLINK_COMM_2, - MAVLINK_COMM_3 -} mavlink_channel_t; -#endif - -/* - * applications can set MAVLINK_COMM_NUM_BUFFERS to the maximum number - * of buffers they will use. If more are used, then the result will be - * a stack overrun - */ -#ifndef MAVLINK_COMM_NUM_BUFFERS -#if (defined linux) | (defined __linux) | (defined __MACH__) | (defined _WIN32) -# define MAVLINK_COMM_NUM_BUFFERS 16 -#else -# define MAVLINK_COMM_NUM_BUFFERS 4 -#endif -#endif - -typedef enum { - MAVLINK_PARSE_STATE_UNINIT=0, - MAVLINK_PARSE_STATE_IDLE, - MAVLINK_PARSE_STATE_GOT_STX, - MAVLINK_PARSE_STATE_GOT_LENGTH, - MAVLINK_PARSE_STATE_GOT_INCOMPAT_FLAGS, - MAVLINK_PARSE_STATE_GOT_COMPAT_FLAGS, - MAVLINK_PARSE_STATE_GOT_SEQ, - MAVLINK_PARSE_STATE_GOT_SYSID, - MAVLINK_PARSE_STATE_GOT_COMPID, - MAVLINK_PARSE_STATE_GOT_MSGID1, - MAVLINK_PARSE_STATE_GOT_MSGID2, - MAVLINK_PARSE_STATE_GOT_MSGID3, - MAVLINK_PARSE_STATE_GOT_PAYLOAD, - MAVLINK_PARSE_STATE_GOT_CRC1, - MAVLINK_PARSE_STATE_GOT_BAD_CRC1, - MAVLINK_PARSE_STATE_SIGNATURE_WAIT -} mavlink_parse_state_t; ///< The state machine for the comm parser - -typedef enum { - MAVLINK_FRAMING_INCOMPLETE=0, - MAVLINK_FRAMING_OK=1, - MAVLINK_FRAMING_BAD_CRC=2, - MAVLINK_FRAMING_BAD_SIGNATURE=3 -} mavlink_framing_t; - -#define MAVLINK_STATUS_FLAG_IN_MAVLINK1 1 // last incoming packet was MAVLink1 -#define MAVLINK_STATUS_FLAG_OUT_MAVLINK1 2 // generate MAVLink1 by default -#define MAVLINK_STATUS_FLAG_IN_SIGNED 4 // last incoming packet was signed and validated -#define MAVLINK_STATUS_FLAG_IN_BADSIG 8 // last incoming packet had a bad signature - -#define MAVLINK_STX_MAVLINK1 0xFE // marker for old protocol - -typedef struct __mavlink_status { - uint8_t msg_received; ///< Number of received messages - uint8_t buffer_overrun; ///< Number of buffer overruns - uint8_t parse_error; ///< Number of parse errors - mavlink_parse_state_t parse_state; ///< Parsing state machine - uint8_t packet_idx; ///< Index in current packet - uint8_t current_rx_seq; ///< Sequence number of last packet received - uint8_t current_tx_seq; ///< Sequence number of last packet sent - uint16_t packet_rx_success_count; ///< Received packets - uint16_t packet_rx_drop_count; ///< Number of packet drops - uint8_t flags; ///< MAVLINK_STATUS_FLAG_* - uint8_t signature_wait; ///< number of signature bytes left to receive - struct __mavlink_signing *signing; ///< optional signing state - struct __mavlink_signing_streams *signing_streams; ///< global record of stream timestamps -} mavlink_status_t; - -/* - a callback function to allow for accepting unsigned packets - */ -typedef bool (*mavlink_accept_unsigned_t)(const mavlink_status_t *status, uint32_t msgid); - -/* - flags controlling signing - */ -#define MAVLINK_SIGNING_FLAG_SIGN_OUTGOING 1 ///< Enable outgoing signing - -typedef enum { - MAVLINK_SIGNING_STATUS_NONE=0, - MAVLINK_SIGNING_STATUS_OK=1, - MAVLINK_SIGNING_STATUS_BAD_SIGNATURE=2, - MAVLINK_SIGNING_STATUS_NO_STREAMS=3, - MAVLINK_SIGNING_STATUS_TOO_MANY_STREAMS=4, - MAVLINK_SIGNING_STATUS_OLD_TIMESTAMP=5, - MAVLINK_SIGNING_STATUS_REPLAY=6, -} mavlink_signing_status_t; - -/* - state of MAVLink signing for this channel - */ -typedef struct __mavlink_signing { - uint8_t flags; ///< MAVLINK_SIGNING_FLAG_* - uint8_t link_id; ///< Same as MAVLINK_CHANNEL - uint64_t timestamp; ///< Timestamp, in microseconds since UNIX epoch GMT - uint8_t secret_key[32]; - mavlink_accept_unsigned_t accept_unsigned_callback; - mavlink_signing_status_t last_status; -} mavlink_signing_t; - -/* - timestamp state of each logical signing stream. This needs to be the same structure for all - connections in order to be secure - */ -#ifndef MAVLINK_MAX_SIGNING_STREAMS -#define MAVLINK_MAX_SIGNING_STREAMS 16 -#endif -typedef struct __mavlink_signing_streams { - uint16_t num_signing_streams; - struct __mavlink_signing_stream { - uint8_t link_id; ///< ID of the link (MAVLINK_CHANNEL) - uint8_t sysid; ///< Remote system ID - uint8_t compid; ///< Remote component ID - uint8_t timestamp_bytes[6]; ///< Timestamp, in microseconds since UNIX epoch GMT - } stream[MAVLINK_MAX_SIGNING_STREAMS]; -} mavlink_signing_streams_t; - - -#define MAVLINK_BIG_ENDIAN 0 -#define MAVLINK_LITTLE_ENDIAN 1 - -#define MAV_MSG_ENTRY_FLAG_HAVE_TARGET_SYSTEM 1 -#define MAV_MSG_ENTRY_FLAG_HAVE_TARGET_COMPONENT 2 - -/* - entry in table of information about each message type - */ -typedef struct __mavlink_msg_entry { - uint32_t msgid; - uint8_t crc_extra; - uint8_t min_msg_len; // minimum message length - uint8_t max_msg_len; // maximum message length (e.g. including mavlink2 extensions) - uint8_t flags; // MAV_MSG_ENTRY_FLAG_* - uint8_t target_system_ofs; // payload offset to target_system, or 0 - uint8_t target_component_ofs; // payload offset to target_component, or 0 -} mavlink_msg_entry_t; - -/* - incompat_flags bits - */ -#define MAVLINK_IFLAG_SIGNED 0x01 -#define MAVLINK_IFLAG_MASK 0x01 // mask of all understood bits - -#ifdef MAVLINK_USE_CXX_NAMESPACE -} // namespace mavlink -#endif diff --git a/TelemetryManager/Inc/official_mavlink_2_library/message_definitions/ASLUAV.xml b/TelemetryManager/Inc/official_mavlink_2_library/message_definitions/ASLUAV.xml deleted file mode 100644 index 4e80a5ac..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/message_definitions/ASLUAV.xml +++ /dev/null @@ -1,294 +0,0 @@ - - - - - common.xml - - - - - Mission command to reset Maximum Power Point Tracker (MPPT) - MPPT number - Empty - Empty - Empty - Empty - Empty - Empty - - - Mission command to perform a power cycle on payload - Complete power cycle - VISensor power cycle - Empty - Empty - Empty - Empty - Empty - - - - - no service - - - link type unknown - - - 2G (GSM/GRPS/EDGE) link - - - 3G link (WCDMA/HSDPA/HSPA) - - - 4G link (LTE) - - - - - not specified - - - HUAWEI LTE USB Stick E3372 - - - - - - Message encoding a command with parameters as scaled integers and additional metadata. Scaling depends on the actual command value. - UTC time, seconds elapsed since 01.01.1970 - Microseconds elapsed since vehicle boot - System ID - Component ID - The coordinate system of the COMMAND, as defined by MAV_FRAME enum - The scheduled action for the mission item, as defined by MAV_CMD enum - false:0, true:1 - autocontinue to next wp - PARAM1, see MAV_CMD enum - PARAM2, see MAV_CMD enum - PARAM3, see MAV_CMD enum - PARAM4, see MAV_CMD enum - PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7 - PARAM6 / local: y position in meters * 1e4, global: longitude in degrees * 10^7 - PARAM7 / z position: global: altitude in meters (MSL, WGS84, AGL or relative to home - depending on frame). - - - Send a command with up to seven parameters to the MAV and additional metadata - UTC time, seconds elapsed since 01.01.1970 - Microseconds elapsed since vehicle boot - System which should execute the command - Component which should execute the command, 0 for all components - Command ID, as defined by MAV_CMD enum. - 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) - Parameter 1, as defined by MAV_CMD enum. - Parameter 2, as defined by MAV_CMD enum. - Parameter 3, as defined by MAV_CMD enum. - Parameter 4, as defined by MAV_CMD enum. - Parameter 5, as defined by MAV_CMD enum. - Parameter 6, as defined by MAV_CMD enum. - Parameter 7, as defined by MAV_CMD enum. - - - Voltage and current sensor data - Power board voltage sensor reading - Power board current sensor reading - Board current sensor 1 reading - Board current sensor 2 reading - - - Maximum Power Point Tracker (MPPT) sensor data for solar module power performance tracking - MPPT last timestamp - MPPT1 voltage - MPPT1 current - MPPT1 pwm - MPPT1 status - MPPT2 voltage - MPPT2 current - MPPT2 pwm - MPPT2 status - MPPT3 voltage - MPPT3 current - MPPT3 pwm - MPPT3 status - - - ASL-fixed-wing controller data - Timestamp - ASLCTRL control-mode (manual, stabilized, auto, etc...) - See sourcecode for a description of these values... - - - Pitch angle - Pitch angle reference - - - - - - - Airspeed reference - - Yaw angle - Yaw angle reference - Roll angle - Roll angle reference - - - - - - - - - ASL-fixed-wing controller debug data - Debug data - Debug data - Debug data - Debug data - Debug data - Debug data - Debug data - Debug data - Debug data - Debug data - Debug data - - - Extended state information for ASLUAVs - Status of the position-indicator LEDs - Status of the IRIDIUM satellite communication system - Status vector for up to 8 servos - Motor RPM - - - - Extended EKF state estimates for ASLUAVs - Time since system start - Magnitude of wind velocity (in lateral inertial plane) - Wind heading angle from North - Z (Down) component of inertial wind velocity - Magnitude of air velocity - Sideslip angle - Angle of attack - - - Off-board controls/commands for ASLUAVs - Time since system start - Elevator command [~] - Throttle command [~] - Throttle 2 command [~] - Left aileron command [~] - Right aileron command [~] - Rudder command [~] - Off-board computer status - - - Atmospheric sensors (temperature, humidity, ...) - Time since system boot - Ambient temperature - Relative humidity - - - Battery pack monitoring data for Li-Ion batteries - Time since system start - Battery pack temperature - Battery pack voltage - Battery pack current - Battery pack state-of-charge - Battery monitor status report bits in Hex - Battery monitor serial number in Hex - Battery monitor safetystatus report bits in Hex - Battery monitor operation status report bits in Hex - Battery pack cell 1 voltage - Battery pack cell 2 voltage - Battery pack cell 3 voltage - Battery pack cell 4 voltage - Battery pack cell 5 voltage - Battery pack cell 6 voltage - - - Fixed-wing soaring (i.e. thermal seeking) data - Timestamp - Timestamp since last mode change - Thermal core updraft strength - Thermal radius - Thermal center latitude - Thermal center longitude - Variance W - Variance R - Variance Lat - Variance Lon - Suggested loiter radius - Suggested loiter direction - Distance to soar point - Expected sink rate at current airspeed, roll and throttle - Measurement / updraft speed at current/local airplane position - Measurement / roll angle tracking error - Expected measurement 1 - Expected measurement 2 - Thermal drift (from estimator prediction step only) - Thermal drift (from estimator prediction step only) - Total specific energy change (filtered) - Debug variable 1 - Debug variable 2 - Control Mode [-] - Data valid [-] - - - Monitoring of sensorpod status - Timestamp in linuxtime (since 1.1.1970) - Rate of ROS topic 1 - Rate of ROS topic 2 - Rate of ROS topic 3 - Rate of ROS topic 4 - Number of recording nodes - Temperature of sensorpod CPU in - Free space available in recordings directory in [Gb] * 1e2 - - - Monitoring of power board status - Timestamp - Power board status register - Power board leds status - Power board system voltage - Power board servo voltage - Power board digital voltage - Power board left motor current sensor - Power board right motor current sensor - Power board analog current sensor - Power board digital current sensor - Power board extension current sensor - Power board aux current sensor - - - Status of GSM modem (connected to onboard computer) - Timestamp (of OBC) - GSM modem used - GSM link type - RSSI as reported by modem (unconverted) - RSRP (LTE) or RSCP (WCDMA) as reported by modem (unconverted) - SINR (LTE) or ECIO (WCDMA) as reported by modem (unconverted) - RSRQ (LTE only) as reported by modem (unconverted) - - - - Status of the SatCom link - Timestamp - Timestamp of the last successful sbd session - Number of failed sessions - Number of successful sessions - Signal quality - Ring call pending - Transmission session pending - Receiving session pending - - - Calibrated airflow angle measurements - Timestamp - Angle of attack - Angle of attack measurement valid - Sideslip angle - Sideslip angle measurement valid - - - diff --git a/TelemetryManager/Inc/official_mavlink_2_library/message_definitions/AVSSUAS.xml b/TelemetryManager/Inc/official_mavlink_2_library/message_definitions/AVSSUAS.xml deleted file mode 100644 index 7138758a..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/message_definitions/AVSSUAS.xml +++ /dev/null @@ -1,198 +0,0 @@ - - - - - - - - - common.xml - 2 - 1 - - - - - AVSS defined command. Set PRS arm statuses. - PRS arm statuses - User defined - User defined - User defined - User defined - User defined - User defined - - - AVSS defined command. Gets PRS arm statuses - User defined - User defined - User defined - User defined - User defined - User defined - User defined - - - AVSS defined command. Get the PRS battery voltage in millivolts - User defined - User defined - User defined - User defined - User defined - User defined - User defined - - - AVSS defined command. Get the PRS error statuses. - User defined - User defined - User defined - User defined - User defined - User defined - User defined - - - AVSS defined command. Set the ATS arming altitude in meters. - ATS arming altitude - User defined - User defined - User defined - User defined - User defined - User defined - - - AVSS defined command. Get the ATS arming altitude in meters. - User defined - User defined - User defined - User defined - User defined - User defined - User defined - - - AVSS defined command. Shuts down the PRS system. - User defined - User defined - User defined - User defined - User defined - User defined - User defined - - - - - AVSS defined command failure reason. PRS not steady. - - - AVSS defined command failure reason. PRS DTM not armed. - - - AVSS defined command failure reason. PRS OTM not armed. - - - - - In manual control mode - - - In attitude mode - - - In GPS mode - - - In hotpoint mode - - - In assisted takeoff mode - - - In auto takeoff mode - - - In auto landing mode - - - In go home mode - - - In sdk control mode - - - In sport mode - - - In force auto landing mode - - - In tripod mode - - - In search mode - - - In engine mode - - - - - In manual control mode - - - In auto takeoff mode - - - In auto landing mode - - - In go home mode - - - In drop mode - - - - - - AVSS PRS system status. - Timestamp (time since PRS boot). - PRS error statuses - Estimated battery run-time without a remote connection and PRS battery voltage - PRS arm statuses - PRS battery charge statuses - - - Drone position. - Timestamp (time since FC boot). - Latitude, expressed - Longitude, expressed - Altitude (MSL). Note that virtually all GPS modules provide both WGS84 and MSL. - Altitude above ground, This altitude is measured by a ultrasound, Laser rangefinder or millimeter-wave radar - This altitude is measured by a barometer - - - Drone IMU data. Quaternion order is w, x, y, z and a zero rotation would be expressed as (1 0 0 0). - Timestamp (time since FC boot). - Quaternion component 1, w (1 in null-rotation) - Quaternion component 2, x (0 in null-rotation) - Quaternion component 3, y (0 in null-rotation) - Quaternion component 4, z (0 in null-rotation) - X acceleration - Y acceleration - Z acceleration - Angular speed around X axis - Angular speed around Y axis - Angular speed around Z axis - - - Drone operation mode. - Timestamp (time since FC boot). - DJI M300 operation mode - horsefly operation mode - - - diff --git a/TelemetryManager/Inc/official_mavlink_2_library/message_definitions/all.xml b/TelemetryManager/Inc/official_mavlink_2_library/message_definitions/all.xml deleted file mode 100644 index 986a5006..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/message_definitions/all.xml +++ /dev/null @@ -1,69 +0,0 @@ - - - - ardupilotmega.xml - - ASLUAV.xml - - common.xml - development.xml - - icarous.xml - - - minimal.xml - - - python_array_test.xml - standard.xml - test.xml - ualberta.xml - - uAvionix.xml - - storm32.xml - - AVSSUAS.xml - - cubepilot.xml - - csAirLink.xml - - - - diff --git a/TelemetryManager/Inc/official_mavlink_2_library/message_definitions/ardupilotmega.xml b/TelemetryManager/Inc/official_mavlink_2_library/message_definitions/ardupilotmega.xml deleted file mode 100644 index 58c3d2da..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/message_definitions/ardupilotmega.xml +++ /dev/null @@ -1,1788 +0,0 @@ - - - common.xml - - uAvionix.xml - icarous.xml - cubepilot.xml - csAirLink.xml - 2 - - - - - - - - - - - - - - - - - - - - - - - - - Set the distance to be repeated on mission resume - Distance. - Empty. - Empty. - Empty. - Empty. - Empty. - Empty. - - - Control attached liquid sprayer - 0: disable sprayer. 1: enable sprayer. - Empty. - Empty. - Empty. - Empty. - Empty. - Empty. - - - Pass instructions onto scripting, a script should be checking for a new command - uint16 ID value to be passed to scripting - float value to be passed to scripting - float value to be passed to scripting - float value to be passed to scripting - Empty. - Empty. - Empty. - - - Execute auxiliary function - Auxiliary Function. - Switch Level. - Empty. - Empty. - Empty. - Empty. - Empty. - - - Mission command to wait for an altitude or downwards vertical speed. This is meant for high altitude balloon launches, allowing the aircraft to be idle until either an altitude is reached or a negative vertical speed is reached (indicating early balloon burst). The wiggle time is how often to wiggle the control surfaces to prevent them seizing up. - Altitude. - Descent speed. - How long to wiggle the control surfaces to prevent them seizing up. - Empty. - Empty. - Empty. - Empty. - - - A system wide power-off event has been initiated. - Empty. - Empty. - Empty. - Empty. - Empty. - Empty. - Empty. - - - - FLY button has been clicked. - Empty. - Empty. - Empty. - Empty. - Empty. - Empty. - Empty. - - - FLY button has been held for 1.5 seconds. - Takeoff altitude. - Empty. - Empty. - Empty. - Empty. - Empty. - Empty. - - - PAUSE button has been clicked. - 1 if Solo is in a shot mode, 0 otherwise. - Empty. - Empty. - Empty. - Empty. - Empty. - Empty. - - - Magnetometer calibration based on fixed position - in earth field given by inclination, declination and intensity. - Magnetic declination. - Magnetic inclination. - Magnetic intensity. - Yaw. - Empty. - Empty. - Empty. - - - Magnetometer calibration based on fixed expected field values. - Field strength X. - Field strength Y. - Field strength Z. - Empty. - Empty. - Empty. - Empty. - - - - Set EKF sensor source set. - Source Set Id. - Empty. - Empty. - Empty. - Empty. - Empty. - Empty. - - - Initiate a magnetometer calibration. - Bitmask of magnetometers to calibrate. Use 0 to calibrate all sensors that can be started (sensors may not start if disabled, unhealthy, etc.). The command will NACK if calibration does not start for a sensor explicitly specified by the bitmask. - Automatically retry on failure (0=no retry, 1=retry). - Save without user input (0=require input, 1=autosave). - Delay. - Autoreboot (0=user reboot, 1=autoreboot). - Empty. - Empty. - - - Accept a magnetometer calibration. - Bitmask of magnetometers that calibration is accepted (0 means all). - Empty. - Empty. - Empty. - Empty. - Empty. - Empty. - - - Cancel a running magnetometer calibration. - Bitmask of magnetometers to cancel a running calibration (0 means all). - Empty. - Empty. - Empty. - Empty. - Empty. - Empty. - - - Used when doing accelerometer calibration. When sent to the GCS tells it what position to put the vehicle in. When sent to the vehicle says what position the vehicle is in. - Position. - Empty. - Empty. - Empty. - Empty. - Empty. - Empty. - - - Reply with the version banner. - Empty. - Empty. - Empty. - Empty. - Empty. - Empty. - Empty. - - - Command autopilot to get into factory test/diagnostic mode. - 0: activate test mode, 1: exit test mode. - Empty. - Empty. - Empty. - Empty. - Empty. - Empty. - - - Causes the gimbal to reset and boot as if it was just powered on. - Empty. - Empty. - Empty. - Empty. - Empty. - Empty. - Empty. - - - Reports progress and success or failure of gimbal axis calibration procedure. - Gimbal axis we're reporting calibration progress for. - Current calibration progress for this axis. - Status of the calibration. - Empty. - Empty. - Empty. - Empty. - - - Starts commutation calibration on the gimbal. - Empty. - Empty. - Empty. - Empty. - Empty. - Empty. - Empty. - - - Erases gimbal application and parameters. - Magic number. - Magic number. - Magic number. - Magic number. - Magic number. - Magic number. - Magic number. - - - - Update the bootloader - Empty - Empty - Empty - Empty - Magic number - set to 290876 to actually flash - Empty - Empty - - - Reset battery capacity for batteries that accumulate consumed battery via integration. - Bitmask of batteries to reset. Least significant bit is for the first battery. - Battery percentage remaining to set. - - - Issue a trap signal to the autopilot process, presumably to enter the debugger. - Magic number - set to 32451 to actually trap. - Empty. - Empty. - Empty. - Empty. - Empty. - Empty. - - - Control onboard scripting. - Scripting command to execute - - - Scripting command as NAV command with wait for completion. - integer command number (0 to 255) - timeout for operation in seconds. Zero means no timeout (0 to 255) - argument1. - argument2. - Empty - Empty - Empty - - - Maintain an attitude for a specified time. - Time to maintain specified attitude and climb rate - Roll angle in degrees (positive is lean right, negative is lean left) - Pitch angle in degrees (positive is lean back, negative is lean forward) - Yaw angle - Climb rate - Empty - Empty - - - Change flight speed at a given rate. This slews the vehicle at a controllable rate between it's previous speed and the new one. (affects GUIDED only. Outside GUIDED, aircraft ignores these commands. Designed for onboard companion-computer command-and-control, not normally operator/GCS control.) - Airspeed or groundspeed. - Target Speed - Acceleration rate, 0 to take effect instantly - Empty - Empty - Empty - Empty - - - Change target altitude at a given rate. This slews the vehicle at a controllable rate between it's previous altitude and the new one. (affects GUIDED only. Outside GUIDED, aircraft ignores these commands. Designed for onboard companion-computer command-and-control, not normally operator/GCS control.) - Empty - Empty - Rate of change, toward new altitude. 0 for maximum rate change. Positive numbers only, as negative numbers will not converge on the new target alt. - Empty - Empty - Empty - Target Altitude - - - Change to target heading at a given rate, overriding previous heading/s. This slews the vehicle at a controllable rate between it's previous heading and the new one. (affects GUIDED only. Exiting GUIDED returns aircraft to normal behaviour defined elsewhere. Designed for onboard companion-computer command-and-control, not normally operator/GCS control.) - course-over-ground or raw vehicle heading. - Target heading. - Maximum centripetal accelearation, ie rate of change, toward new heading. - Empty - Empty - Empty - Empty - - - Provide an external position estimate for use when dead-reckoning. This is meant to be used for occasional position resets that may be provided by a external system such as a remote pilot using landmarks over a video link. - Timestamp that this message was sent as a time in the transmitters time domain. The sender should wrap this time back to zero based on required timing accuracy for the application and the limitations of a 32 bit float. For example, wrapping at 10 hours would give approximately 1ms accuracy. Recipient must handle time wrap in any timing jitter correction applied to this field. Wrap rollover time should not be at not more than 250 seconds, which would give approximately 10 microsecond accuracy. - The time spent in processing the sensor data that is the basis for this position. The recipient can use this to improve time alignment of the data. Set to zero if not known. - estimated one standard deviation accuracy of the measurement. Set to NaN if not known. - Empty - Latitude - Longitude - Altitude, not used. Should be sent as NaN. May be supported in a future version of this message. - - - - - Start a REPL session. - - - End a REPL session. - - - Stop execution of scripts. - - - Stop execution of scripts and restart. - - - - - - Pre-initialization. - - - Disabled. - - - Checking limits. - - - A limit has been breached. - - - Taking action e.g. Return/RTL. - - - We're no longer in breach of a limit. - - - - - - Pre-initialization. - - - Disabled. - - - Checking limits. - - - - - Flags in RALLY_POINT message. - - Flag set when requiring favorable winds for landing. - - - Flag set when plane is to immediately descend to break altitude and land without GCS intervention. Flag not set when plane is to loiter at Rally point until commanded to land. - - - - - - Camera heartbeat, announce camera component ID at 1Hz. - - - Camera image triggered. - - - Camera connection lost. - - - Camera unknown error. - - - Camera battery low. Parameter p1 shows reported voltage. - - - Camera storage low. Parameter p1 shows reported shots remaining. - - - Camera storage low. Parameter p1 shows reported video minutes remaining. - - - - - - Shooting photos, not video. - - - Shooting video, not stills. - - - Unable to achieve requested exposure (e.g. shutter speed too low). - - - Closed loop feedback from camera, we know for sure it has successfully taken a picture. - - - Open loop camera, an image trigger has been requested but we can't know for sure it has successfully taken a picture. - - - - - - Gimbal is powered on but has not started initializing yet. - - - Gimbal is currently running calibration on the pitch axis. - - - Gimbal is currently running calibration on the roll axis. - - - Gimbal is currently running calibration on the yaw axis. - - - Gimbal has finished calibrating and initializing, but is relaxed pending reception of first rate command from copter. - - - Gimbal is actively stabilizing. - - - Gimbal is relaxed because it missed more than 10 expected rate command messages in a row. Gimbal will move back to active mode when it receives a new rate command. - - - - - Gimbal yaw axis. - - - Gimbal pitch axis. - - - Gimbal roll axis. - - - - - Axis calibration is in progress. - - - Axis calibration succeeded. - - - Axis calibration failed. - - - - - Whether or not this axis requires calibration is unknown at this time. - - - This axis requires calibration. - - - This axis does not require calibration. - - - - - - No GoPro connected. - - - The detected GoPro is not HeroBus compatible. - - - A HeroBus compatible GoPro is connected. - - - An unrecoverable error was encountered with the connected GoPro, it may require a power cycle. - - - - - - GoPro is currently recording. - - - - - The write message with ID indicated succeeded. - - - The write message with ID indicated failed. - - - - - (Get/Set). - - - (Get/Set). - - - (___/Set). - - - (Get/___). - - - (Get/___). - - - (Get/Set). - - - - (Get/Set). - - - (Get/Set). - - - (Get/Set). - - - (Get/Set). - - - (Get/Set) Hero 3+ Only. - - - (Get/Set) Hero 3+ Only. - - - (Get/Set) Hero 3+ Only. - - - (Get/Set) Hero 3+ Only. - - - (Get/Set) Hero 3+ Only. - - - (Get/Set). - - - - (Get/Set). - - - - - Video mode. - - - Photo mode. - - - Burst mode, Hero 3+ only. - - - Time lapse mode, Hero 3+ only. - - - Multi shot mode, Hero 4 only. - - - Playback mode, Hero 4 only, silver only except when LCD or HDMI is connected to black. - - - Playback mode, Hero 4 only. - - - Mode not yet known. - - - - - 848 x 480 (480p). - - - 1280 x 720 (720p). - - - 1280 x 960 (960p). - - - 1920 x 1080 (1080p). - - - 1920 x 1440 (1440p). - - - 2704 x 1440 (2.7k-17:9). - - - 2704 x 1524 (2.7k-16:9). - - - 2704 x 2028 (2.7k-4:3). - - - 3840 x 2160 (4k-16:9). - - - 4096 x 2160 (4k-17:9). - - - 1280 x 720 (720p-SuperView). - - - 1920 x 1080 (1080p-SuperView). - - - 2704 x 1520 (2.7k-SuperView). - - - 3840 x 2160 (4k-SuperView). - - - - - 12 FPS. - - - 15 FPS. - - - 24 FPS. - - - 25 FPS. - - - 30 FPS. - - - 48 FPS. - - - 50 FPS. - - - 60 FPS. - - - 80 FPS. - - - 90 FPS. - - - 100 FPS. - - - 120 FPS. - - - 240 FPS. - - - 12.5 FPS. - - - - - 0x00: Wide. - - - 0x01: Medium. - - - 0x02: Narrow. - - - - - 0=NTSC, 1=PAL. - - - - - 5MP Medium. - - - 7MP Medium. - - - 7MP Wide. - - - 10MP Wide. - - - 12MP Wide. - - - - - Auto. - - - 3000K. - - - 5500K. - - - 6500K. - - - Camera Raw. - - - - - Auto. - - - Neutral. - - - - - ISO 400. - - - ISO 800 (Only Hero 4). - - - ISO 1600. - - - ISO 3200 (Only Hero 4). - - - ISO 6400. - - - - - Low Sharpness. - - - Medium Sharpness. - - - High Sharpness. - - - - - -5.0 EV (Hero 3+ Only). - - - -4.5 EV (Hero 3+ Only). - - - -4.0 EV (Hero 3+ Only). - - - -3.5 EV (Hero 3+ Only). - - - -3.0 EV (Hero 3+ Only). - - - -2.5 EV (Hero 3+ Only). - - - -2.0 EV. - - - -1.5 EV. - - - -1.0 EV. - - - -0.5 EV. - - - 0.0 EV. - - - +0.5 EV. - - - +1.0 EV. - - - +1.5 EV. - - - +2.0 EV. - - - +2.5 EV (Hero 3+ Only). - - - +3.0 EV (Hero 3+ Only). - - - +3.5 EV (Hero 3+ Only). - - - +4.0 EV (Hero 3+ Only). - - - +4.5 EV (Hero 3+ Only). - - - +5.0 EV (Hero 3+ Only). - - - - - Charging disabled. - - - Charging enabled. - - - - - Unknown gopro model. - - - Hero 3+ Silver (HeroBus not supported by GoPro). - - - Hero 3+ Black. - - - Hero 4 Silver. - - - Hero 4 Black. - - - - - 3 Shots / 1 Second. - - - 5 Shots / 1 Second. - - - 10 Shots / 1 Second. - - - 10 Shots / 2 Second. - - - 10 Shots / 3 Second (Hero 4 Only). - - - 30 Shots / 1 Second. - - - 30 Shots / 2 Second. - - - 30 Shots / 3 Second. - - - 30 Shots / 6 Second. - - - - - Switch Low. - - - Switch Middle. - - - Switch High. - - - - - - LED patterns off (return control to regular vehicle control). - - - LEDs show pattern during firmware update. - - - Custom Pattern using custom bytes fields. - - - - - Flags in EKF_STATUS message. - - Set if EKF's attitude estimate is good. - - - Set if EKF's horizontal velocity estimate is good. - - - Set if EKF's vertical velocity estimate is good. - - - Set if EKF's horizontal position (relative) estimate is good. - - - Set if EKF's horizontal position (absolute) estimate is good. - - - Set if EKF's vertical position (absolute) estimate is good. - - - Set if EKF's vertical position (above ground) estimate is good. - - - EKF is in constant position mode and does not know it's absolute or relative position. - - - Set if EKF's predicted horizontal position (relative) estimate is good. - - - Set if EKF's predicted horizontal position (absolute) estimate is good. - - - Set if EKF has never been healthy. - - - - - - - - - - - - Special ACK block numbers control activation of dataflash log streaming. - - - - UAV to stop sending DataFlash blocks. - - - - UAV to start sending DataFlash blocks. - - - - - Possible remote log data block statuses. - - This block has NOT been received. - - - This block has been received. - - - - Bus types for device operations. - - I2C Device operation. - - - SPI Device operation. - - - - Deepstall flight stage. - - Flying to the landing point. - - - Building an estimate of the wind. - - - Waiting to breakout of the loiter to fly the approach. - - - Flying to the first arc point to turn around to the landing point. - - - Turning around back to the deepstall landing point. - - - Approaching the landing point. - - - Stalling and steering towards the land point. - - - - A mapping of plane flight modes for custom_mode field of heartbeat. - - - - - - - - - - - - - - - - - - - - - - - - - - - A mapping of copter flight modes for custom_mode field of heartbeat. - - - - - - - - - - - - - - - - - - - - - - - - - - - - A mapping of sub flight modes for custom_mode field of heartbeat. - - - - - - - - - - - - A mapping of rover flight modes for custom_mode field of heartbeat. - - - - - - - - - - - - - - - A mapping of antenna tracker flight modes for custom_mode field of heartbeat. - - - - - - - - - The type of parameter for the OSD parameter editor. - - - - - - - - - - - - The error type for the OSD parameter editor. - - - - - - - - - Offsets and calibrations values for hardware sensors. This makes it easier to debug the calibration process. - Magnetometer X offset. - Magnetometer Y offset. - Magnetometer Z offset. - Magnetic declination. - Raw pressure from barometer. - Raw temperature from barometer. - Gyro X calibration. - Gyro Y calibration. - Gyro Z calibration. - Accel X calibration. - Accel Y calibration. - Accel Z calibration. - - - - Set the magnetometer offsets - System ID. - Component ID. - Magnetometer X offset. - Magnetometer Y offset. - Magnetometer Z offset. - - - State of autopilot RAM. - Heap top. - Free memory. - - Free memory (32 bit). - - - Raw ADC output. - ADC output 1. - ADC output 2. - ADC output 3. - ADC output 4. - ADC output 5. - ADC output 6. - - - - Configure on-board Camera Control System. - System ID. - Component ID. - Mode enumeration from 1 to N //P, TV, AV, M, etc. (0 means ignore). - Divisor number //e.g. 1000 means 1/1000 (0 means ignore). - F stop number x 10 //e.g. 28 means 2.8 (0 means ignore). - ISO enumeration from 1 to N //e.g. 80, 100, 200, Etc (0 means ignore). - Exposure type enumeration from 1 to N (0 means ignore). - Command Identity (incremental loop: 0 to 255). //A command sent multiple times will be executed or pooled just once. - Main engine cut-off time before camera trigger (0 means no cut-off). - Extra parameters enumeration (0 means ignore). - Correspondent value to given extra_param. - - - Control on-board Camera Control System to take shots. - System ID. - Component ID. - 0: stop, 1: start or keep it up //Session control e.g. show/hide lens. - 1 to N //Zoom's absolute position (0 means ignore). - -100 to 100 //Zooming step value to offset zoom from the current position. - 0: unlock focus or keep unlocked, 1: lock focus or keep locked, 3: re-lock focus. - 0: ignore, 1: shot or start filming. - Command Identity (incremental loop: 0 to 255)//A command sent multiple times will be executed or pooled just once. - Extra parameters enumeration (0 means ignore). - Correspondent value to given extra_param. - - - - Message to configure a camera mount, directional antenna, etc. - System ID. - Component ID. - Mount operating mode. - (1 = yes, 0 = no). - (1 = yes, 0 = no). - (1 = yes, 0 = no). - - - Message to control a camera mount, directional antenna, etc. - System ID. - Component ID. - Pitch (centi-degrees) or lat (degE7), depending on mount mode. - Roll (centi-degrees) or lon (degE7) depending on mount mode. - Yaw (centi-degrees) or alt (cm) depending on mount mode. - If "1" it will save current trimmed position on EEPROM (just valid for NEUTRAL and LANDING). - - - Message with some status from autopilot to GCS about camera or antenna mount. - System ID. - Component ID. - Pitch. - Roll. - Yaw. - - Mount operating mode. - - - - A fence point. Used to set a point when from GCS -> MAV. Also used to return a point from MAV -> GCS. - System ID. - Component ID. - Point index (first point is 1, 0 is for return point). - Total number of points (for sanity checking). - Latitude of point. - Longitude of point. - - - Request a current fence point from MAV. - System ID. - Component ID. - Point index (first point is 1, 0 is for return point). - - - Status of DCM attitude estimator. - X gyro drift estimate. - Y gyro drift estimate. - Z gyro drift estimate. - Average accel_weight. - Average renormalisation value. - Average error_roll_pitch value. - Average error_yaw value. - - - Status of simulation environment, if used. - Roll angle. - Pitch angle. - Yaw angle. - X acceleration. - Y acceleration. - Z acceleration. - Angular speed around X axis. - Angular speed around Y axis. - Angular speed around Z axis. - Latitude. - Longitude. - - - Status of key hardware. - Board voltage. - I2C error count. - - - Status generated by radio. - Local signal strength. - Remote signal strength. - How full the tx buffer is. - Background noise level. - Remote background noise level. - Receive errors. - Count of error corrected packets. - - - - Status of AP_Limits. Sent in extended status stream when AP_Limits is enabled. - State of AP_Limits. - Time (since boot) of last breach. - Time (since boot) of last recovery action. - Time (since boot) of last successful recovery. - Time (since boot) of last all-clear. - Number of fence breaches. - AP_Limit_Module bitfield of enabled modules. - AP_Limit_Module bitfield of required modules. - AP_Limit_Module bitfield of triggered modules. - - - Wind estimation. - Wind direction (that wind is coming from). - Wind speed in ground plane. - Vertical wind speed. - - - Data packet, size 16. - Data type. - Data length. - Raw data. - - - Data packet, size 32. - Data type. - Data length. - Raw data. - - - Data packet, size 64. - Data type. - Data length. - Raw data. - - - Data packet, size 96. - Data type. - Data length. - Raw data. - - - Rangefinder reporting. - Distance. - Raw voltage if available, zero otherwise. - - - Airspeed auto-calibration. - GPS velocity north. - GPS velocity east. - GPS velocity down. - Differential pressure. - Estimated to true airspeed ratio. - Airspeed ratio. - EKF state x. - EKF state y. - EKF state z. - EKF Pax. - EKF Pby. - EKF Pcz. - - - - A rally point. Used to set a point when from GCS -> MAV. Also used to return a point from MAV -> GCS. - System ID. - Component ID. - Point index (first point is 0). - Total number of points (for sanity checking). - Latitude of point. - Longitude of point. - Transit / loiter altitude relative to home. - - Break altitude relative to home. - Heading to aim for when landing. - Configuration flags. - - - Request a current rally point from MAV. MAV should respond with a RALLY_POINT message. MAV should not respond if the request is invalid. - System ID. - Component ID. - Point index (first point is 0). - - - Status of compassmot calibration. - Throttle. - Current. - Interference. - Motor Compensation X. - Motor Compensation Y. - Motor Compensation Z. - - - Status of secondary AHRS filter if available. - Roll angle. - Pitch angle. - Yaw angle. - Altitude (MSL). - Latitude. - Longitude. - - - - Camera Event. - Image timestamp (since UNIX epoch, according to camera clock). - System ID. - - Camera ID. - - Image index. - - Event type. - Parameter 1 (meaning depends on event_id, see CAMERA_STATUS_TYPES enum). - Parameter 2 (meaning depends on event_id, see CAMERA_STATUS_TYPES enum). - Parameter 3 (meaning depends on event_id, see CAMERA_STATUS_TYPES enum). - Parameter 4 (meaning depends on event_id, see CAMERA_STATUS_TYPES enum). - - - - Camera Capture Feedback. - Image timestamp (since UNIX epoch), as passed in by CAMERA_STATUS message (or autopilot if no CCB). - System ID. - - Camera ID. - - Image index. - - Latitude. - Longitude. - Altitude (MSL). - Altitude (Relative to HOME location). - Camera Roll angle (earth frame, +-180). - - Camera Pitch angle (earth frame, +-180). - - Camera Yaw (earth frame, 0-360, true). - - Focal Length. - - Feedback flags. - - - Completed image captures. - - - - 2nd Battery status - Voltage. - Battery current, -1: autopilot does not measure the current. - - - Status of third AHRS filter if available. This is for ANU research group (Ali and Sean). - Roll angle. - Pitch angle. - Yaw angle. - Altitude (MSL). - Latitude. - Longitude. - Test variable1. - Test variable2. - Test variable3. - Test variable4. - - - Request the autopilot version from the system/component. - System ID. - Component ID. - - - - Send a block of log data to remote location. - System ID. - Component ID. - Log data block sequence number. - Log data block. - - - Send Status of each log block that autopilot board might have sent. - System ID. - Component ID. - Log data block sequence number. - Log data block status. - - - Control vehicle LEDs. - System ID. - Component ID. - Instance (LED instance to control or 255 for all LEDs). - Pattern (see LED_PATTERN_ENUM). - Custom Byte Length. - Custom Bytes. - - - Reports progress of compass calibration. - Compass being calibrated. - Bitmask of compasses being calibrated. - Calibration Status. - Attempt number. - Completion percentage. - Bitmask of sphere sections (see http://en.wikipedia.org/wiki/Geodesic_grid). - Body frame direction vector for display. - Body frame direction vector for display. - Body frame direction vector for display. - - - - - EKF Status message including flags and variances. - Flags. - - Velocity variance. - - Horizontal Position variance. - Vertical Position variance. - Compass variance. - Terrain Altitude variance. - - Airspeed variance. - - - - PID tuning information. - Axis. - Desired rate. - Achieved rate. - FF component. - P component. - I component. - D component. - - Slew rate. - P/D oscillation modifier. - - - Deepstall path planning. - Landing latitude. - Landing longitude. - Final heading start point, latitude. - Final heading start point, longitude. - Arc entry point, latitude. - Arc entry point, longitude. - Altitude. - Distance the aircraft expects to travel during the deepstall. - Deepstall cross track error (only valid when in DEEPSTALL_STAGE_LAND). - Deepstall stage. - - - 3 axis gimbal measurements. - System ID. - Component ID. - Time since last update. - Delta angle X. - Delta angle Y. - Delta angle X. - Delta velocity X. - Delta velocity Y. - Delta velocity Z. - Joint ROLL. - Joint EL. - Joint AZ. - - - Control message for rate gimbal. - System ID. - Component ID. - Demanded angular rate X. - Demanded angular rate Y. - Demanded angular rate Z. - - - 100 Hz gimbal torque command telemetry. - System ID. - Component ID. - Roll Torque Command. - Elevation Torque Command. - Azimuth Torque Command. - - - - Heartbeat from a HeroBus attached GoPro. - Status. - Current capture mode. - Additional status bits. - - - - Request a GOPRO_COMMAND response from the GoPro. - System ID. - Component ID. - Command ID. - - - Response from a GOPRO_COMMAND get request. - Command ID. - Status. - Value. - - - Request to set a GOPRO_COMMAND with a desired. - System ID. - Component ID. - Command ID. - Value. - - - Response from a GOPRO_COMMAND set request. - Command ID. - Status. - - - - - RPM sensor output. - RPM Sensor1. - RPM Sensor2. - - - - Read registers for a device. - System ID. - Component ID. - Request ID - copied to reply. - The bus type. - Bus number. - Bus address. - Name of device on bus (for SPI). - First register to read. - Count of registers to read. - - Bank number. - - - Read registers reply. - Request ID - copied from request. - 0 for success, anything else is failure code. - Starting register. - Count of bytes read. - Reply data. - - Bank number. - - - Write registers for a device. - System ID. - Component ID. - Request ID - copied to reply. - The bus type. - Bus number. - Bus address. - Name of device on bus (for SPI). - First register to write. - Count of registers to write. - Write data. - - Bank number. - - - Write registers reply. - Request ID - copied from request. - 0 for success, anything else is failure code. - - - - Adaptive Controller tuning information. - Axis. - Desired rate. - Achieved rate. - Error between model and vehicle. - Theta estimated state predictor. - Omega estimated state predictor. - Sigma estimated state predictor. - Theta derivative. - Omega derivative. - Sigma derivative. - Projection operator value. - Projection operator derivative. - u adaptive controlled output command. - - - - Camera vision based attitude and position deltas. - Timestamp (synced to UNIX time or since system boot). - Time since the last reported camera frame. - Defines a rotation vector [roll, pitch, yaw] to the current MAV_FRAME_BODY_FRD from the previous MAV_FRAME_BODY_FRD. - Change in position to the current MAV_FRAME_BODY_FRD from the previous FRAME_BODY_FRD rotated to the current MAV_FRAME_BODY_FRD. - Normalised confidence value from 0 to 100. - - - - Angle of Attack and Side Slip Angle. - Timestamp (since boot or Unix epoch). - Angle of Attack. - Side Slip Angle. - - - ESC Telemetry Data for ESCs 1 to 4, matching data sent by BLHeli ESCs. - Temperature. - Voltage. - Current. - Total current. - RPM (eRPM). - count of telemetry packets received (wraps at 65535). - - - ESC Telemetry Data for ESCs 5 to 8, matching data sent by BLHeli ESCs. - Temperature. - Voltage. - Current. - Total current. - RPM (eRPM). - count of telemetry packets received (wraps at 65535). - - - ESC Telemetry Data for ESCs 9 to 12, matching data sent by BLHeli ESCs. - Temperature. - Voltage. - Current. - Total current. - RPM (eRPM). - count of telemetry packets received (wraps at 65535). - - - Configure an OSD parameter slot. - System ID. - Component ID. - Request ID - copied to reply. - OSD parameter screen index. - OSD parameter display index. - Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string - Config type. - OSD parameter minimum value. - OSD parameter maximum value. - OSD parameter increment. - - - Configure OSD parameter reply. - Request ID - copied from request. - Config error type. - - - Read a configured an OSD parameter slot. - System ID. - Component ID. - Request ID - copied to reply. - OSD parameter screen index. - OSD parameter display index. - - - Read configured OSD parameter reply. - Request ID - copied from request. - Config error type. - Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string - Config type. - OSD parameter minimum value. - OSD parameter maximum value. - OSD parameter increment. - - - - - Obstacle located as a 3D vector. - Timestamp (time since system boot). - Class id of the distance sensor type. - Coordinate frame of reference. - Unique ID given to each obstacle so that its movement can be tracked. Use UINT16_MAX if object ID is unknown or cannot be determined. - X position of the obstacle. - Y position of the obstacle. - Z position of the obstacle. - Minimum distance the sensor can measure. - Maximum distance the sensor can measure. - - - Water depth - Timestamp (time since system boot) - Onboard ID of the sensor - Sensor data healthy (0=unhealthy, 1=healthy) - Latitude - Longitude - Altitude (MSL) of vehicle - Roll angle - Pitch angle - Yaw angle - Distance (uncorrected) - Water temperature - - - The MCU status, giving MCU temperature and voltage. The min and max voltages are to allow for detecting power supply instability. - MCU instance - MCU Internal temperature - MCU voltage - MCU voltage minimum - MCU voltage maximum - - - diff --git a/TelemetryManager/Inc/official_mavlink_2_library/message_definitions/common.xml b/TelemetryManager/Inc/official_mavlink_2_library/message_definitions/common.xml deleted file mode 100644 index 1f897798..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/message_definitions/common.xml +++ /dev/null @@ -1,7606 +0,0 @@ - - - standard.xml - 3 - 0 - - - These values define the type of firmware release. These values indicate the first version or release of this type. For example the first alpha release would be 64, the second would be 65. - - development release - - - alpha release - - - beta release - - - release candidate - - - official stable release - - - - Flags to report failure cases over the high latency telemtry. - - GPS failure. - - - Differential pressure sensor failure. - - - Absolute pressure sensor failure. - - - Accelerometer sensor failure. - - - Gyroscope sensor failure. - - - Magnetometer sensor failure. - - - Terrain subsystem failure. - - - Battery failure/critical low battery. - - - RC receiver failure/no rc connection. - - - Offboard link failure. - - - Engine failure. - - - Geofence violation. - - - Estimator failure, for example measurement rejection or large variances. - - - Mission failure. - - - - Actions that may be specified in MAV_CMD_OVERRIDE_GOTO to override mission execution. - - Hold at the current position. - - - Continue with the next item in mission execution. - - - Hold at the current position of the system - - - Hold at the position specified in the parameters of the DO_HOLD action - - - - These defines are predefined OR-combined mode flags. There is no need to use values from this enum, but it - simplifies the use of the mode flags. Note that manual input is enabled in all modes as a safety override. - - System is not ready to fly, booting, calibrating, etc. No flag is set. - - - System is allowed to be active, under assisted RC control. - - - System is allowed to be active, under assisted RC control. - - - System is allowed to be active, under manual (RC) control, no stabilization - - - System is allowed to be active, under manual (RC) control, no stabilization - - - System is allowed to be active, under autonomous control, manual setpoint - - - System is allowed to be active, under autonomous control, manual setpoint - - - System is allowed to be active, under autonomous control and navigation (the trajectory is decided onboard and not pre-programmed by waypoints) - - - System is allowed to be active, under autonomous control and navigation (the trajectory is decided onboard and not pre-programmed by waypoints) - - - UNDEFINED mode. This solely depends on the autopilot - use with caution, intended for developers only. - - - UNDEFINED mode. This solely depends on the autopilot - use with caution, intended for developers only. - - - - These encode the sensors whose status is sent as part of the SYS_STATUS message. - - 0x01 3D gyro - - - 0x02 3D accelerometer - - - 0x04 3D magnetometer - - - 0x08 absolute pressure - - - 0x10 differential pressure - - - 0x20 GPS - - - 0x40 optical flow - - - 0x80 computer vision position - - - 0x100 laser based position - - - 0x200 external ground truth (Vicon or Leica) - - - 0x400 3D angular rate control - - - 0x800 attitude stabilization - - - 0x1000 yaw position - - - 0x2000 z/altitude control - - - 0x4000 x/y position control - - - 0x8000 motor outputs / control - - - 0x10000 rc receiver - - - 0x20000 2nd 3D gyro - - - 0x40000 2nd 3D accelerometer - - - 0x80000 2nd 3D magnetometer - - - 0x100000 geofence - - - 0x200000 AHRS subsystem health - - - 0x400000 Terrain subsystem health - - - 0x800000 Motors are reversed - - - 0x1000000 Logging - - - 0x2000000 Battery - - - 0x4000000 Proximity - - - 0x8000000 Satellite Communication - - - 0x10000000 pre-arm check status. Always healthy when armed - - - 0x20000000 Avoidance/collision prevention - - - 0x40000000 propulsion (actuator, esc, motor or propellor) - - - 0x80000000 Extended bit-field are used for further sensor status bits (needs to be set in onboard_control_sensors_present only) - - - - These encode the sensors whose status is sent as part of the SYS_STATUS message in the extended fields. - - 0x01 Recovery system (parachute, balloon, retracts etc) - - - - Coordinate frames used by MAVLink. Not all frames are supported by all commands, messages, or vehicles. - - Global frames use the following naming conventions: - - "GLOBAL": Global coordinate frame with WGS84 latitude/longitude and altitude positive over mean sea level (MSL) by default. - The following modifiers may be used with "GLOBAL": - - "RELATIVE_ALT": Altitude is relative to the vehicle home position rather than MSL. - - "TERRAIN_ALT": Altitude is relative to ground level rather than MSL. - - "INT": Latitude/longitude (in degrees) are scaled by multiplying by 1E7. - - Local frames use the following naming conventions: - - "LOCAL": Origin of local frame is fixed relative to earth. Unless otherwise specified this origin is the origin of the vehicle position-estimator ("EKF"). - - "BODY": Origin of local frame travels with the vehicle. NOTE, "BODY" does NOT indicate alignment of frame axis with vehicle attitude. - - "OFFSET": Deprecated synonym for "BODY" (origin travels with the vehicle). Not to be used for new frames. - - Some deprecated frames do not follow these conventions (e.g. MAV_FRAME_BODY_NED and MAV_FRAME_BODY_OFFSET_NED). - - - Global (WGS84) coordinate frame + MSL altitude. First value / x: latitude, second value / y: longitude, third value / z: positive altitude over mean sea level (MSL). - - - NED local tangent frame (x: North, y: East, z: Down) with origin fixed relative to earth. - - - NOT a coordinate frame, indicates a mission command. - - - - Global (WGS84) coordinate frame + altitude relative to the home position. - First value / x: latitude, second value / y: longitude, third value / z: positive altitude with 0 being at the altitude of the home position. - - - - ENU local tangent frame (x: East, y: North, z: Up) with origin fixed relative to earth. - - - Global (WGS84) coordinate frame (scaled) + MSL altitude. First value / x: latitude in degrees*1E7, second value / y: longitude in degrees*1E7, third value / z: positive altitude over mean sea level (MSL). - - - - Global (WGS84) coordinate frame (scaled) + altitude relative to the home position. - First value / x: latitude in degrees*1E7, second value / y: longitude in degrees*1E7, third value / z: positive altitude with 0 being at the altitude of the home position. - - - - NED local tangent frame (x: North, y: East, z: Down) with origin that travels with the vehicle. - - - - Same as MAV_FRAME_LOCAL_NED when used to represent position values. Same as MAV_FRAME_BODY_FRD when used with velocity/acceleration values. - - - - This is the same as MAV_FRAME_BODY_FRD. - - - Global (WGS84) coordinate frame with AGL altitude (at the waypoint coordinate). First value / x: latitude in degrees, second value / y: longitude in degrees, third value / z: positive altitude in meters with 0 being at ground level in terrain model. - - - Global (WGS84) coordinate frame (scaled) with AGL altitude (at the waypoint coordinate). First value / x: latitude in degrees*1E7, second value / y: longitude in degrees*1E7, third value / z: positive altitude in meters with 0 being at ground level in terrain model. - - - FRD local frame aligned to the vehicle's attitude (x: Forward, y: Right, z: Down) with an origin that travels with vehicle. - - - - MAV_FRAME_BODY_FLU - Body fixed frame of reference, Z-up (x: Forward, y: Left, z: Up). - - - - MAV_FRAME_MOCAP_NED - Odometry local coordinate frame of data given by a motion capture system, Z-down (x: North, y: East, z: Down). - - - - MAV_FRAME_MOCAP_ENU - Odometry local coordinate frame of data given by a motion capture system, Z-up (x: East, y: North, z: Up). - - - - MAV_FRAME_VISION_NED - Odometry local coordinate frame of data given by a vision estimation system, Z-down (x: North, y: East, z: Down). - - - - MAV_FRAME_VISION_ENU - Odometry local coordinate frame of data given by a vision estimation system, Z-up (x: East, y: North, z: Up). - - - - MAV_FRAME_ESTIM_NED - Odometry local coordinate frame of data given by an estimator running onboard the vehicle, Z-down (x: North, y: East, z: Down). - - - - MAV_FRAME_ESTIM_ENU - Odometry local coordinate frame of data given by an estimator running onboard the vehicle, Z-up (x: East, y: North, z: Up). - - - FRD local tangent frame (x: Forward, y: Right, z: Down) with origin fixed relative to earth. The forward axis is aligned to the front of the vehicle in the horizontal plane. - - - FLU local tangent frame (x: Forward, y: Left, z: Up) with origin fixed relative to earth. The forward axis is aligned to the front of the vehicle in the horizontal plane. - - - - - - - - - - - - - - - - - - - - - - - - - Actions following geofence breach. - - Disable fenced mode. If used in a plan this would mean the next fence is disabled. - - - Fly to geofence MAV_CMD_NAV_FENCE_RETURN_POINT in GUIDED mode. Note: This action is only supported by ArduPlane, and may not be supported in all versions. - - - Report fence breach, but don't take action - - - Fly to geofence MAV_CMD_NAV_FENCE_RETURN_POINT with manual throttle control in GUIDED mode. Note: This action is only supported by ArduPlane, and may not be supported in all versions. - - - Return/RTL mode. - - - Hold at current location. - - - Termination failsafe. Motors are shut down (some flight stacks may trigger other failsafe actions). - - - Land at current location. - - - - - No last fence breach - - - Breached minimum altitude - - - Breached maximum altitude - - - Breached fence boundary - - - - - Actions being taken to mitigate/prevent fence breach - - Unknown - - - No actions being taken - - - Velocity limiting active to prevent breach - - - - - - Enumeration of possible mount operation modes. This message is used by obsolete/deprecated gimbal messages. - - Load and keep safe position (Roll,Pitch,Yaw) from permant memory and stop stabilization - - - Load and keep neutral position (Roll,Pitch,Yaw) from permanent memory. - - - Load neutral position and start MAVLink Roll,Pitch,Yaw control with stabilization - - - Load neutral position and start RC Roll,Pitch,Yaw control with stabilization - - - Load neutral position and start to point to Lat,Lon,Alt - - - Gimbal tracks system with specified system ID - - - Gimbal tracks home position - - - - Gimbal device (low level) capability flags (bitmap). - - Gimbal device supports a retracted position. - - - Gimbal device supports a horizontal, forward looking position, stabilized. - - - Gimbal device supports rotating around roll axis. - - - Gimbal device supports to follow a roll angle relative to the vehicle. - - - Gimbal device supports locking to a roll angle (generally that's the default with roll stabilized). - - - Gimbal device supports rotating around pitch axis. - - - Gimbal device supports to follow a pitch angle relative to the vehicle. - - - Gimbal device supports locking to a pitch angle (generally that's the default with pitch stabilized). - - - Gimbal device supports rotating around yaw axis. - - - Gimbal device supports to follow a yaw angle relative to the vehicle (generally that's the default). - - - Gimbal device supports locking to an absolute heading, i.e., yaw angle relative to North (earth frame, often this is an option available). - - - Gimbal device supports yawing/panning infinetely (e.g. using slip disk). - - - Gimbal device supports yaw angles and angular velocities relative to North (earth frame). This usually requires support by an autopilot via AUTOPILOT_STATE_FOR_GIMBAL_DEVICE. Support can go on and off during runtime, which is reported by the flag GIMBAL_DEVICE_FLAGS_CAN_ACCEPT_YAW_IN_EARTH_FRAME. - - - Gimbal device supports radio control inputs as an alternative input for controlling the gimbal orientation. - - - - Gimbal manager high level capability flags (bitmap). The first 16 bits are identical to the GIMBAL_DEVICE_CAP_FLAGS. However, the gimbal manager does not need to copy the flags from the gimbal but can also enhance the capabilities and thus add flags. - - Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_RETRACT. - - - Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_NEUTRAL. - - - Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_AXIS. - - - Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_FOLLOW. - - - Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_LOCK. - - - Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_AXIS. - - - Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_FOLLOW. - - - Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_LOCK. - - - Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_AXIS. - - - Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_FOLLOW. - - - Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_LOCK. - - - Based on GIMBAL_DEVICE_CAP_FLAGS_SUPPORTS_INFINITE_YAW. - - - Based on GIMBAL_DEVICE_CAP_FLAGS_SUPPORTS_YAW_IN_EARTH_FRAME. - - - Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_RC_INPUTS. - - - Gimbal manager supports to point to a local position. - - - Gimbal manager supports to point to a global latitude, longitude, altitude position. - - - - Flags for gimbal device (lower level) operation. - - Set to retracted safe position (no stabilization), takes presedence over all other flags. - - - Set to neutral/default position, taking precedence over all other flags except RETRACT. Neutral is commonly forward-facing and horizontal (roll=pitch=yaw=0) but may be any orientation. - - - Lock roll angle to absolute angle relative to horizon (not relative to vehicle). This is generally the default with a stabilizing gimbal. - - - Lock pitch angle to absolute angle relative to horizon (not relative to vehicle). This is generally the default with a stabilizing gimbal. - - - Lock yaw angle to absolute angle relative to North (not relative to vehicle). If this flag is set, the yaw angle and z component of angular velocity are relative to North (earth frame, x-axis pointing North), else they are relative to the vehicle heading (vehicle frame, earth frame rotated so that the x-axis is pointing forward). - - - Yaw angle and z component of angular velocity are relative to the vehicle heading (vehicle frame, earth frame rotated such that the x-axis is pointing forward). - - - Yaw angle and z component of angular velocity are relative to North (earth frame, x-axis is pointing North). - - - Gimbal device can accept yaw angle inputs relative to North (earth frame). This flag is only for reporting (attempts to set this flag are ignored). - - - The gimbal orientation is set exclusively by the RC signals feed to the gimbal's radio control inputs. MAVLink messages for setting the gimbal orientation (GIMBAL_DEVICE_SET_ATTITUDE) are ignored. - - - The gimbal orientation is determined by combining/mixing the RC signals feed to the gimbal's radio control inputs and the MAVLink messages for setting the gimbal orientation (GIMBAL_DEVICE_SET_ATTITUDE). How these two controls are combined or mixed is not defined by the protocol but is up to the implementation. - - - - Flags for high level gimbal manager operation The first 16 bits are identical to the GIMBAL_DEVICE_FLAGS. - - Based on GIMBAL_DEVICE_FLAGS_RETRACT. - - - Based on GIMBAL_DEVICE_FLAGS_NEUTRAL. - - - Based on GIMBAL_DEVICE_FLAGS_ROLL_LOCK. - - - Based on GIMBAL_DEVICE_FLAGS_PITCH_LOCK. - - - Based on GIMBAL_DEVICE_FLAGS_YAW_LOCK. - - - Based on GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME. - - - Based on GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME. - - - Based on GIMBAL_DEVICE_FLAGS_ACCEPTS_YAW_IN_EARTH_FRAME. - - - Based on GIMBAL_DEVICE_FLAGS_RC_EXCLUSIVE. - - - Based on GIMBAL_DEVICE_FLAGS_RC_MIXED. - - - - Gimbal device (low level) error flags (bitmap, 0 means no error) - - Gimbal device is limited by hardware roll limit. - - - Gimbal device is limited by hardware pitch limit. - - - Gimbal device is limited by hardware yaw limit. - - - There is an error with the gimbal encoders. - - - There is an error with the gimbal power source. - - - There is an error with the gimbal motors. - - - There is an error with the gimbal's software. - - - There is an error with the gimbal's communication. - - - Gimbal device is currently calibrating. - - - Gimbal device is not assigned to a gimbal manager. - - - - - Gripper actions. - - Gripper release cargo. - - - Gripper grab onto cargo. - - - - - Winch actions. - - Allow motor to freewheel. - - - Wind or unwind specified length of line, optionally using specified rate. - - - Wind or unwind line at specified rate. - - - Perform the locking sequence to relieve motor while in the fully retracted position. Only action and instance command parameters are used, others are ignored. - - - Sequence of drop, slow down, touch down, reel up, lock. Only action and instance command parameters are used, others are ignored. - - - Engage motor and hold current position. Only action and instance command parameters are used, others are ignored. - - - Return the reel to the fully retracted position. Only action and instance command parameters are used, others are ignored. - - - Load the reel with line. The winch will calculate the total loaded length and stop when the tension exceeds a threshold. Only action and instance command parameters are used, others are ignored. - - - Spool out the entire length of the line. Only action and instance command parameters are used, others are ignored. - - - Spools out just enough to present the hook to the user to load the payload. Only action and instance command parameters are used, others are ignored - - - - - Generalized UAVCAN node health - - The node is functioning properly. - - - A critical parameter went out of range or the node has encountered a minor failure. - - - The node has encountered a major failure. - - - The node has suffered a fatal malfunction. - - - - - Generalized UAVCAN node mode - - The node is performing its primary functions. - - - The node is initializing; this mode is entered immediately after startup. - - - The node is under maintenance. - - - The node is in the process of updating its software. - - - The node is no longer available online. - - - - - Indicates the ESC connection type. - - Traditional PPM ESC. - - - Serial Bus connected ESC. - - - One Shot PPM ESC. - - - I2C ESC. - - - CAN-Bus ESC. - - - DShot ESC. - - - - - Flags to report ESC failures. - - No ESC failure. - - - Over current failure. - - - Over voltage failure. - - - Over temperature failure. - - - Over RPM failure. - - - Inconsistent command failure i.e. out of bounds. - - - Motor stuck failure. - - - Generic ESC failure. - - - - Flags to indicate the status of camera storage. - - Storage is missing (no microSD card loaded for example.) - - - Storage present but unformatted. - - - Storage present and ready. - - - Camera does not supply storage status information. Capacity information in STORAGE_INFORMATION fields will be ignored. - - - - Flags to indicate the type of storage. - - Storage type is not known. - - - Storage type is USB device. - - - Storage type is SD card. - - - Storage type is microSD card. - - - Storage type is CFast. - - - Storage type is CFexpress. - - - Storage type is XQD. - - - Storage type is HD mass storage type. - - - Storage type is other, not listed type. - - - - Flags to indicate usage for a particular storage (see STORAGE_INFORMATION.storage_usage and MAV_CMD_SET_STORAGE_USAGE). - - Always set to 1 (indicates STORAGE_INFORMATION.storage_usage is supported). - - - Storage for saving photos. - - - Storage for saving videos. - - - Storage for saving logs. - - - - Yaw behaviour during orbit flight. - - Vehicle front points to the center (default). - - - Vehicle front holds heading when message received. - - - Yaw uncontrolled. - - - Vehicle front follows flight path (tangential to circle). - - - Yaw controlled by RC input. - - - - Possible responses from a WIFI_CONFIG_AP message. - - Undefined response. Likely an indicative of a system that doesn't support this request. - - - Changes accepted. - - - Changes rejected. - - - Invalid Mode. - - - Invalid SSID. - - - Invalid Password. - - - - Possible responses from a CELLULAR_CONFIG message. - - Changes accepted. - - - Invalid APN. - - - Invalid PIN. - - - Changes rejected. - - - PUK is required to unblock SIM card. - - - - WiFi Mode. - - WiFi mode is undefined. - - - WiFi configured as an access point. - - - WiFi configured as a station connected to an existing local WiFi network. - - - WiFi disabled. - - - - Supported component metadata types. These are used in the "general" metadata file returned by COMPONENT_METADATA to provide information about supported metadata types. The types are not used directly in MAVLink messages. - - General information about the component. General metadata includes information about other metadata types supported by the component. Files of this type must be supported, and must be downloadable from vehicle using a MAVLink FTP URI. - - - Parameter meta data. - - - Meta data that specifies which commands and command parameters the vehicle supports. (WIP) - - - Meta data that specifies external non-MAVLink peripherals. - - - Meta data for the events interface. - - - Meta data for actuator configuration (motors, servos and vehicle geometry) and testing. - - - - Actuator configuration, used to change a setting on an actuator. Component information metadata can be used to know which outputs support which commands. - - Do nothing. - - - Command the actuator to beep now. - - - Permanently set the actuator (ESC) to 3D mode (reversible thrust). - - - Permanently set the actuator (ESC) to non 3D mode (non-reversible thrust). - - - Permanently set the actuator (ESC) to spin direction 1 (which can be clockwise or counter-clockwise). - - - Permanently set the actuator (ESC) to spin direction 2 (opposite of direction 1). - - - - Actuator output function. Values greater or equal to 1000 are autopilot-specific. - - No function (disabled). - - - Motor 1 - - - Motor 2 - - - Motor 3 - - - Motor 4 - - - Motor 5 - - - Motor 6 - - - Motor 7 - - - Motor 8 - - - Motor 9 - - - Motor 10 - - - Motor 11 - - - Motor 12 - - - Motor 13 - - - Motor 14 - - - Motor 15 - - - Motor 16 - - - Servo 1 - - - Servo 2 - - - Servo 3 - - - Servo 4 - - - Servo 5 - - - Servo 6 - - - Servo 7 - - - Servo 8 - - - Servo 9 - - - Servo 10 - - - Servo 11 - - - Servo 12 - - - Servo 13 - - - Servo 14 - - - Servo 15 - - - Servo 16 - - - - Enable axes that will be tuned via autotuning. Used in MAV_CMD_DO_AUTOTUNE_ENABLE. - - Flight stack tunes axis according to its default settings. - - - Autotune roll axis. - - - Autotune pitch axis. - - - Autotune yaw axis. - - - - - Actions for reading/writing parameters between persistent and volatile storage when using MAV_CMD_PREFLIGHT_STORAGE. - (Commonly parameters are loaded from persistent storage (flash/EEPROM) into volatile storage (RAM) on startup and written back when they are changed.) - - - Read all parameters from persistent storage. Replaces values in volatile storage. - - - Write all parameter values to persistent storage (flash/EEPROM) - - - Reset all user configurable parameters to their default value (including airframe selection, sensor calibration data, safety settings, and so on). Does not reset values that contain operation counters and vehicle computed statistics. - - - Reset only sensor calibration parameters to factory defaults (or firmware default if not available) - - - Reset all parameters, including operation counters, to default values - - - - - Actions for reading and writing plan information (mission, rally points, geofence) between persistent and volatile storage when using MAV_CMD_PREFLIGHT_STORAGE. - (Commonly missions are loaded from persistent storage (flash/EEPROM) into volatile storage (RAM) on startup and written back when they are changed.) - - - Read current mission data from persistent storage - - - Write current mission data to persistent storage - - - Erase all mission data stored on the vehicle (both persistent and volatile storage) - - - - - - - - Commands to be executed by the MAV. They can be executed on user request, or as part of a mission script. If the action is used in a mission, the parameter mapping to the waypoint/mission message is as follows: Param 1, Param 2, Param 3, Param 4, X: Param 5, Y:Param 6, Z:Param 7. This command list is similar what ARINC 424 is for commercial aircraft: A data format how to interpret waypoint/mission data. NaN and INT32_MAX may be used in float/integer params (respectively) to indicate optional/default values (e.g. to use the component's current yaw or latitude rather than a specific value). See https://mavlink.io/en/guide/xml_schema.html#MAV_CMD for information about the structure of the MAV_CMD entries - - Navigate to waypoint. This is intended for use in missions (for guided commands outside of missions use MAV_CMD_DO_REPOSITION). - Hold time. (ignored by fixed wing, time to stay at waypoint for rotary wing) - Acceptance radius (if the sphere with this radius is hit, the waypoint counts as reached) - 0 to pass through the WP, if > 0 radius to pass by WP. Positive value for clockwise orbit, negative value for counter-clockwise orbit. Allows trajectory control. - Desired yaw angle at waypoint (rotary wing). NaN to use the current system yaw heading mode (e.g. yaw towards next waypoint, yaw to home, etc.). - Latitude - Longitude - Altitude - - - Loiter around this waypoint an unlimited amount of time - Empty - Empty - Loiter radius around waypoint for forward-only moving vehicles (not multicopters). If positive loiter clockwise, else counter-clockwise - Desired yaw angle. NaN to use the current system yaw heading mode (e.g. yaw towards next waypoint, yaw to home, etc.). - Latitude - Longitude - Altitude - - - Loiter around this waypoint for X turns - Number of turns. - Leave loiter circle only once heading towards the next waypoint (0 = False) - Loiter radius around waypoint for forward-only moving vehicles (not multicopters). If positive loiter clockwise, else counter-clockwise - Loiter circle exit location and/or path to next waypoint ("xtrack") for forward-only moving vehicles (not multicopters). 0 for the vehicle to converge towards the center xtrack when it leaves the loiter (the line between the centers of the current and next waypoint), 1 to converge to the direct line between the location that the vehicle exits the loiter radius and the next waypoint. Otherwise the angle (in degrees) between the tangent of the loiter circle and the center xtrack at which the vehicle must leave the loiter (and converge to the center xtrack). NaN to use the current system default xtrack behaviour. - Latitude - Longitude - Altitude - - - Loiter at the specified latitude, longitude and altitude for a certain amount of time. Multicopter vehicles stop at the point (within a vehicle-specific acceptance radius). Forward-only moving vehicles (e.g. fixed-wing) circle the point with the specified radius/direction. If the Heading Required parameter (2) is non-zero forward moving aircraft will only leave the loiter circle once heading towards the next waypoint. - Loiter time (only starts once Lat, Lon and Alt is reached). - Leave loiter circle only once heading towards the next waypoint (0 = False) - Loiter radius around waypoint for forward-only moving vehicles (not multicopters). If positive loiter clockwise, else counter-clockwise. - Loiter circle exit location and/or path to next waypoint ("xtrack") for forward-only moving vehicles (not multicopters). 0 for the vehicle to converge towards the center xtrack when it leaves the loiter (the line between the centers of the current and next waypoint), 1 to converge to the direct line between the location that the vehicle exits the loiter radius and the next waypoint. Otherwise the angle (in degrees) between the tangent of the loiter circle and the center xtrack at which the vehicle must leave the loiter (and converge to the center xtrack). NaN to use the current system default xtrack behaviour. - Latitude - Longitude - Altitude - - - Return to launch location - Empty - Empty - Empty - Empty - Empty - Empty - Empty - - - Land at location. - Minimum target altitude if landing is aborted (0 = undefined/use system default). - Precision land mode. - Empty. - Desired yaw angle. NaN to use the current system yaw heading mode (e.g. yaw towards next waypoint, yaw to home, etc.). - Latitude. - Longitude. - Landing altitude (ground level in current frame). - - - Takeoff from ground / hand. Vehicles that support multiple takeoff modes (e.g. VTOL quadplane) should take off using the currently configured mode. - Minimum pitch (if airspeed sensor present), desired pitch without sensor - Empty - Empty - Yaw angle (if magnetometer present), ignored without magnetometer. NaN to use the current system yaw heading mode (e.g. yaw towards next waypoint, yaw to home, etc.). - Latitude - Longitude - Altitude - - - Land at local position (local frame only) - Landing target number (if available) - Maximum accepted offset from desired landing position - computed magnitude from spherical coordinates: d = sqrt(x^2 + y^2 + z^2), which gives the maximum accepted distance between the desired landing position and the position where the vehicle is about to land - Landing descend rate - Desired yaw angle - Y-axis position - X-axis position - Z-axis / ground level position - - - Takeoff from local position (local frame only) - Minimum pitch (if airspeed sensor present), desired pitch without sensor - Empty - Takeoff ascend rate - Yaw angle (if magnetometer or another yaw estimation source present), ignored without one of these - Y-axis position - X-axis position - Z-axis position - - - Vehicle following, i.e. this waypoint represents the position of a moving vehicle - Following logic to use (e.g. loitering or sinusoidal following) - depends on specific autopilot implementation - Ground speed of vehicle to be followed - Radius around waypoint. If positive loiter clockwise, else counter-clockwise - Desired yaw angle. - Latitude - Longitude - Altitude - - - Continue on the current course and climb/descend to specified altitude. When the altitude is reached continue to the next command (i.e., don't proceed to the next command until the desired altitude is reached. - Climb or Descend (0 = Neutral, command completes when within 5m of this command's altitude, 1 = Climbing, command completes when at or above this command's altitude, 2 = Descending, command completes when at or below this command's altitude. - Empty - Empty - Empty - Empty - Empty - Desired altitude - - - Begin loiter at the specified Latitude and Longitude. If Lat=Lon=0, then loiter at the current position. Don't consider the navigation command complete (don't leave loiter) until the altitude has been reached. Additionally, if the Heading Required parameter is non-zero the aircraft will not leave the loiter until heading toward the next waypoint. - Leave loiter circle only once heading towards the next waypoint (0 = False) - Loiter radius around waypoint for forward-only moving vehicles (not multicopters). If positive loiter clockwise, negative counter-clockwise, 0 means no change to standard loiter. - Empty - Loiter circle exit location and/or path to next waypoint ("xtrack") for forward-only moving vehicles (not multicopters). 0 for the vehicle to converge towards the center xtrack when it leaves the loiter (the line between the centers of the current and next waypoint), 1 to converge to the direct line between the location that the vehicle exits the loiter radius and the next waypoint. Otherwise the angle (in degrees) between the tangent of the loiter circle and the center xtrack at which the vehicle must leave the loiter (and converge to the center xtrack). NaN to use the current system default xtrack behaviour. - Latitude - Longitude - Altitude - - - Begin following a target - System ID (of the FOLLOW_TARGET beacon). Send 0 to disable follow-me and return to the default position hold mode. - Reserved - Reserved - Altitude mode: 0: Keep current altitude, 1: keep altitude difference to target, 2: go to a fixed altitude above home. - Altitude above home. (used if mode=2) - Reserved - Time to land in which the MAV should go to the default position hold mode after a message RX timeout. - - - Reposition the MAV after a follow target command has been sent - Camera q1 (where 0 is on the ray from the camera to the tracking device) - Camera q2 - Camera q3 - Camera q4 - altitude offset from target - X offset from target - Y offset from target - - - - - Start orbiting on the circumference of a circle defined by the parameters. Setting values to NaN/INT32_MAX (as appropriate) results in using defaults. - Radius of the circle. Positive: orbit clockwise. Negative: orbit counter-clockwise. NaN: Use vehicle default radius, or current radius if already orbiting. - Tangential Velocity. NaN: Use vehicle default velocity, or current velocity if already orbiting. - Yaw behavior of the vehicle. - Orbit around the centre point for this many radians (i.e. for a three-quarter orbit set 270*Pi/180). 0: Orbit forever. NaN: Use vehicle default, or current value if already orbiting. - Center point latitude (if no MAV_FRAME specified) / X coordinate according to MAV_FRAME. INT32_MAX (or NaN if sent in COMMAND_LONG): Use current vehicle position, or current center if already orbiting. - Center point longitude (if no MAV_FRAME specified) / Y coordinate according to MAV_FRAME. INT32_MAX (or NaN if sent in COMMAND_LONG): Use current vehicle position, or current center if already orbiting. - Center point altitude (MSL) (if no MAV_FRAME specified) / Z coordinate according to MAV_FRAME. NaN: Use current vehicle altitude. - - - - Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicle's control system to control the vehicle attitude and the attitude of various sensors such as cameras. - Region of interest mode. - Waypoint index/ target ID. (see MAV_ROI enum) - ROI index (allows a vehicle to manage multiple ROI's) - Empty - x the location of the fixed ROI (see MAV_FRAME) - y - z - - - Control autonomous path planning on the MAV. - 0: Disable local obstacle avoidance / local path planning (without resetting map), 1: Enable local path planning, 2: Enable and reset local path planning - 0: Disable full path planning (without resetting map), 1: Enable, 2: Enable and reset map/occupancy grid, 3: Enable and reset planned route, but not occupancy grid - Empty - Yaw angle at goal - Latitude/X of goal - Longitude/Y of goal - Altitude/Z of goal - - - Navigate to waypoint using a spline path. - Hold time. (ignored by fixed wing, time to stay at waypoint for rotary wing) - Empty - Empty - Empty - Latitude/X of goal - Longitude/Y of goal - Altitude/Z of goal - - - Takeoff from ground using VTOL mode, and transition to forward flight with specified heading. The command should be ignored by vehicles that dont support both VTOL and fixed-wing flight (multicopters, boats,etc.). - Empty - Front transition heading. - Empty - Yaw angle. NaN to use the current system yaw heading mode (e.g. yaw towards next waypoint, yaw to home, etc.). - Latitude - Longitude - Altitude - - - Land using VTOL mode - Landing behaviour. - Empty - Approach altitude (with the same reference as the Altitude field). NaN if unspecified. - Yaw angle. NaN to use the current system yaw heading mode (e.g. yaw towards next waypoint, yaw to home, etc.). - Latitude - Longitude - Altitude (ground level) relative to the current coordinate frame. NaN to use system default landing altitude (ignore value). - - - - hand control over to an external controller - On / Off (> 0.5f on) - Empty - Empty - Empty - Empty - Empty - Empty - - - Delay the next navigation command a number of seconds or until a specified time - Delay (-1 to enable time-of-day fields) - hour (24h format, UTC, -1 to ignore) - minute (24h format, UTC, -1 to ignore) - second (24h format, UTC, -1 to ignore) - Empty - Empty - Empty - - - Descend and place payload. Vehicle moves to specified location, descends until it detects a hanging payload has reached the ground, and then releases the payload. If ground is not detected before the reaching the maximum descent value (param1), the command will complete without releasing the payload. - Maximum distance to descend. - Empty - Empty - Empty - Latitude - Longitude - Altitude - - - NOP - This command is only used to mark the upper limit of the NAV/ACTION commands in the enumeration - Empty - Empty - Empty - Empty - Empty - Empty - Empty - - - Delay mission state machine. - Delay - Empty - Empty - Empty - Empty - Empty - Empty - - - Ascend/descend to target altitude at specified rate. Delay mission state machine until desired altitude reached. - Descent / Ascend rate. - Empty - Empty - Empty - Empty - Empty - Target Altitude - - - Delay mission state machine until within desired distance of next NAV point. - Distance. - Empty - Empty - Empty - Empty - Empty - Empty - - - Reach a certain target angle. - target angle, 0 is north - angular speed - direction: -1: counter clockwise, 1: clockwise - 0: absolute angle, 1: relative offset - Empty - Empty - Empty - - - NOP - This command is only used to mark the upper limit of the CONDITION commands in the enumeration - Empty - Empty - Empty - Empty - Empty - Empty - Empty - - - Set system mode. - Mode - Custom mode - this is system specific, please refer to the individual autopilot specifications for details. - Custom sub mode - this is system specific, please refer to the individual autopilot specifications for details. - Empty - Empty - Empty - Empty - - - Jump to the desired command in the mission list. Repeat this action only the specified number of times - Sequence number - Repeat count - Empty - Empty - Empty - Empty - Empty - - - Change speed and/or throttle set points. The value persists until it is overridden or there is a mode change. - Speed type (0=Airspeed, 1=Ground Speed, 2=Climb Speed, 3=Descent Speed) - Speed (-1 indicates no change, -2 indicates return to default vehicle speed) - Throttle (-1 indicates no change, -2 indicates return to default vehicle throttle value) - - - - - - - - Sets the home position to either to the current position or a specified position. - The home position is the default position that the system will return to and land on. - The position is set automatically by the system during the takeoff (and may also be set using this command). - Note: the current home position may be emitted in a HOME_POSITION message on request (using MAV_CMD_REQUEST_MESSAGE with param1=242). - - Use current (1=use current location, 0=use specified location) - Empty - Empty - Yaw angle. NaN to use default heading - Latitude - Longitude - Altitude - - - Set a system parameter. Caution! Use of this command requires knowledge of the numeric enumeration value of the parameter. - Parameter number - Parameter value - Empty - Empty - Empty - Empty - Empty - - - Set a relay to a condition. - Relay instance number. - Setting. (1=on, 0=off, others possible depending on system hardware) - Empty - Empty - Empty - Empty - Empty - - - Cycle a relay on and off for a desired number of cycles with a desired period. - Relay instance number. - Cycle count. - Cycle time. - Empty - Empty - Empty - Empty - - - Set a servo to a desired PWM value. - Servo instance number. - Pulse Width Modulation. - Empty - Empty - Empty - Empty - Empty - - - Cycle a between its nominal setting and a desired PWM for a desired number of cycles with a desired period. - Servo instance number. - Pulse Width Modulation. - Cycle count. - Cycle time. - Empty - Empty - Empty - - - Terminate flight immediately. - Flight termination immediately and irreversably terminates the current flight, returning the vehicle to ground. - The vehicle will ignore RC or other input until it has been power-cycled. - Termination may trigger safety measures, including: disabling motors and deployment of parachute on multicopters, and setting flight surfaces to initiate a landing pattern on fixed-wing). - On multicopters without a parachute it may trigger a crash landing. - Support for this command can be tested using the protocol bit: MAV_PROTOCOL_CAPABILITY_FLIGHT_TERMINATION. - Support for this command can also be tested by sending the command with param1=0 (< 0.5); the ACK should be either MAV_RESULT_FAILED or MAV_RESULT_UNSUPPORTED. - - Flight termination activated if > 0.5. Otherwise not activated and ACK with MAV_RESULT_FAILED. - Empty - Empty - Empty - Empty - Empty - Empty - - - Change altitude set point. - Altitude. - Frame of new altitude. - Empty - Empty - Empty - Empty - Empty - - - Sets actuators (e.g. servos) to a desired value. The actuator numbers are mapped to specific outputs (e.g. on any MAIN or AUX PWM or UAVCAN) using a flight-stack specific mechanism (i.e. a parameter). - Actuator 1 value, scaled from [-1 to 1]. NaN to ignore. - Actuator 2 value, scaled from [-1 to 1]. NaN to ignore. - Actuator 3 value, scaled from [-1 to 1]. NaN to ignore. - Actuator 4 value, scaled from [-1 to 1]. NaN to ignore. - Actuator 5 value, scaled from [-1 to 1]. NaN to ignore. - Actuator 6 value, scaled from [-1 to 1]. NaN to ignore. - Index of actuator set (i.e if set to 1, Actuator 1 becomes Actuator 7) - - - Mission command to perform a landing. This is used as a marker in a mission to tell the autopilot where a sequence of mission items that represents a landing starts. - It may also be sent via a COMMAND_LONG to trigger a landing, in which case the nearest (geographically) landing sequence in the mission will be used. - The Latitude/Longitude/Altitude is optional, and may be set to 0 if not needed. If specified then it will be used to help find the closest landing sequence. - - Empty - Empty - Empty - Empty - Latitude - Longitude - Altitude - - - Mission command to perform a landing from a rally point. - Break altitude - Landing speed - Empty - Empty - Empty - Empty - Empty - - - Mission command to safely abort an autonomous landing. - Altitude - Empty - Empty - Empty - Empty - Empty - Empty - - - Reposition the vehicle to a specific WGS84 global position. This command is intended for guided commands (for missions use MAV_CMD_NAV_WAYPOINT instead). - Ground speed, less than 0 (-1) for default - Bitmask of option flags. - Loiter radius for planes. Positive values only, direction is controlled by Yaw value. A value of zero or NaN is ignored. - Yaw heading. NaN to use the current system yaw heading mode (e.g. yaw towards next waypoint, yaw to home, etc.). For planes indicates loiter direction (0: clockwise, 1: counter clockwise) - Latitude - Longitude - Altitude - - - If in a GPS controlled position mode, hold the current position or continue. - 0: Pause current mission or reposition command, hold current position. 1: Continue mission. A VTOL capable vehicle should enter hover mode (multicopter and VTOL planes). A plane should loiter with the default loiter radius. - Reserved - Reserved - Reserved - Reserved - Reserved - Reserved - - - Set moving direction to forward or reverse. - Direction (0=Forward, 1=Reverse) - Empty - Empty - Empty - Empty - Empty - Empty - - - Sets the region of interest (ROI) to a location. This can then be used by the vehicle's control system to control the vehicle attitude and the attitude of various sensors such as cameras. This command can be sent to a gimbal manager but not to a gimbal device. A gimbal is not to react to this message. - Component ID of gimbal device to address (or 1-6 for non-MAVLink gimbal), 0 for all gimbal device components. Send command multiple times for more than one gimbal (but not all gimbals). - Empty - Empty - Empty - Latitude of ROI location - Longitude of ROI location - Altitude of ROI location - - - Sets the region of interest (ROI) to be toward next waypoint, with optional pitch/roll/yaw offset. This can then be used by the vehicle's control system to control the vehicle attitude and the attitude of various sensors such as cameras. This command can be sent to a gimbal manager but not to a gimbal device. A gimbal device is not to react to this message. - Component ID of gimbal device to address (or 1-6 for non-MAVLink gimbal), 0 for all gimbal device components. Send command multiple times for more than one gimbal (but not all gimbals). - Empty - Empty - Empty - Pitch offset from next waypoint, positive pitching up - Roll offset from next waypoint, positive rolling to the right - Yaw offset from next waypoint, positive yawing to the right - - - Cancels any previous ROI command returning the vehicle/sensors to default flight characteristics. This can then be used by the vehicle's control system to control the vehicle attitude and the attitude of various sensors such as cameras. This command can be sent to a gimbal manager but not to a gimbal device. A gimbal device is not to react to this message. After this command the gimbal manager should go back to manual input if available, and otherwise assume a neutral position. - Component ID of gimbal device to address (or 1-6 for non-MAVLink gimbal), 0 for all gimbal device components. Send command multiple times for more than one gimbal (but not all gimbals). - Empty - Empty - Empty - Empty - Empty - Empty - - - Mount tracks system with specified system ID. Determination of target vehicle position may be done with GLOBAL_POSITION_INT or any other means. This command can be sent to a gimbal manager but not to a gimbal device. A gimbal device is not to react to this message. - System ID - Component ID of gimbal device to address (or 1-6 for non-MAVLink gimbal), 0 for all gimbal device components. Send command multiple times for more than one gimbal (but not all gimbals). - - - Control onboard camera system. - Camera ID (-1 for all) - Transmission: 0: disabled, 1: enabled compressed, 2: enabled raw - Transmission mode: 0: video stream, >0: single images every n seconds - Recording: 0: disabled, 1: enabled compressed, 2: enabled raw - Empty - Empty - Empty - - - - Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicle's control system to control the vehicle attitude and the attitude of various sensors such as cameras. - Region of interest mode. - Waypoint index/ target ID (depends on param 1). - Region of interest index. (allows a vehicle to manage multiple ROI's) - Empty - MAV_ROI_WPNEXT: pitch offset from next waypoint, MAV_ROI_LOCATION: latitude - MAV_ROI_WPNEXT: roll offset from next waypoint, MAV_ROI_LOCATION: longitude - MAV_ROI_WPNEXT: yaw offset from next waypoint, MAV_ROI_LOCATION: altitude - - - - Configure digital camera. This is a fallback message for systems that have not yet implemented PARAM_EXT_XXX messages and camera definition files (see https://mavlink.io/en/services/camera_def.html ). - Modes: P, TV, AV, M, Etc. - Shutter speed: Divisor number for one second. - Aperture: F stop number. - ISO number e.g. 80, 100, 200, Etc. - Exposure type enumerator. - Command Identity. - Main engine cut-off time before camera trigger. (0 means no cut-off) - - - Control digital camera. This is a fallback message for systems that have not yet implemented PARAM_EXT_XXX messages and camera definition files (see https://mavlink.io/en/services/camera_def.html ). - Session control e.g. show/hide lens - Zoom's absolute position - Zooming step value to offset zoom from the current position - Focus Locking, Unlocking or Re-locking - Shooting Command - Command Identity - Test shot identifier. If set to 1, image will only be captured, but not counted towards internal frame count. - - - - This message has been superseded by MAV_CMD_DO_GIMBAL_MANAGER_CONFIGURE. The message can still be used to communicate with legacy gimbals implementing it. - Mission command to configure a camera or antenna mount - Mount operation mode - stabilize roll? (1 = yes, 0 = no) - stabilize pitch? (1 = yes, 0 = no) - stabilize yaw? (1 = yes, 0 = no) - roll input (0 = angle body frame, 1 = angular rate, 2 = angle absolute frame) - pitch input (0 = angle body frame, 1 = angular rate, 2 = angle absolute frame) - yaw input (0 = angle body frame, 1 = angular rate, 2 = angle absolute frame) - - - - This message is ambiguous and inconsistent. It has been superseded by MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW and MAV_CMD_DO_SET_ROI_*. The message can still be used to communicate with legacy gimbals implementing it. - Mission command to control a camera or antenna mount - pitch depending on mount mode (degrees or degrees/second depending on pitch input). - roll depending on mount mode (degrees or degrees/second depending on roll input). - yaw depending on mount mode (degrees or degrees/second depending on yaw input). - altitude depending on mount mode. - latitude, set if appropriate mount mode. - longitude, set if appropriate mount mode. - Mount mode. - - - Mission command to set camera trigger distance for this flight. The camera is triggered each time this distance is exceeded. This command can also be used to set the shutter integration time for the camera. - Camera trigger distance. 0 to stop triggering. - Camera shutter integration time. -1 or 0 to ignore - Trigger camera once immediately. (0 = no trigger, 1 = trigger) - Empty - Empty - Empty - Empty - - - Mission command to enable the geofence - enable? (0=disable, 1=enable, 2=disable_floor_only) - Empty - Empty - Empty - Empty - Empty - Empty - - - Mission item/command to release a parachute or enable/disable auto release. - Action - Empty - Empty - Empty - Empty - Empty - Empty - - - Command to perform motor test. - Motor instance number (from 1 to max number of motors on the vehicle). - Throttle type (whether the Throttle Value in param3 is a percentage, PWM value, etc.) - Throttle value. - Timeout between tests that are run in sequence. - Motor count. Number of motors to test in sequence: 0/1=one motor, 2= two motors, etc. The Timeout (param4) is used between tests. - Motor test order. - Empty - - - Change to/from inverted flight. - Inverted flight. (0=normal, 1=inverted) - Empty - Empty - Empty - Empty - Empty - Empty - - - Mission command to operate a gripper. - Gripper instance number. - Gripper action to perform. - Empty - Empty - Empty - Empty - Empty - - - Enable/disable autotune. - Enable (1: enable, 0:disable). - Specify which axis are autotuned. 0 indicates autopilot default settings. - Empty. - Empty. - Empty. - Empty. - Empty. - - - Sets a desired vehicle turn angle and speed change. - Yaw angle to adjust steering by. - Speed. - Final angle. (0=absolute, 1=relative) - Empty - Empty - Empty - Empty - - - Mission command to set camera trigger interval for this flight. If triggering is enabled, the camera is triggered each time this interval expires. This command can also be used to set the shutter integration time for the camera. - Camera trigger cycle time. -1 or 0 to ignore. - Camera shutter integration time. Should be less than trigger cycle time. -1 or 0 to ignore. - Empty - Empty - Empty - Empty - Empty - - - - Mission command to control a camera or antenna mount, using a quaternion as reference. - quaternion param q1, w (1 in null-rotation) - quaternion param q2, x (0 in null-rotation) - quaternion param q3, y (0 in null-rotation) - quaternion param q4, z (0 in null-rotation) - Empty - Empty - Empty - - - set id of master controller - System ID - Component ID - Empty - Empty - Empty - Empty - Empty - - - Set limits for external control - Timeout - maximum time that external controller will be allowed to control vehicle. 0 means no timeout. - Altitude (MSL) min - if vehicle moves below this alt, the command will be aborted and the mission will continue. 0 means no lower altitude limit. - Altitude (MSL) max - if vehicle moves above this alt, the command will be aborted and the mission will continue. 0 means no upper altitude limit. - Horizontal move limit - if vehicle moves more than this distance from its location at the moment the command was executed, the command will be aborted and the mission will continue. 0 means no horizontal move limit. - Empty - Empty - Empty - - - Control vehicle engine. This is interpreted by the vehicles engine controller to change the target engine state. It is intended for vehicles with internal combustion engines - 0: Stop engine, 1:Start Engine - 0: Warm start, 1:Cold start. Controls use of choke where applicable - Height delay. This is for commanding engine start only after the vehicle has gained the specified height. Used in VTOL vehicles during takeoff to start engine after the aircraft is off the ground. Zero for no delay. - Empty - Empty - Empty - Empty - - - - Set the mission item with sequence number seq as the current item and emit MISSION_CURRENT (whether or not the mission number changed). - If a mission is currently being executed, the system will continue to this new mission item on the shortest path, skipping any intermediate mission items. - Note that mission jump repeat counters are not reset unless param2 is set (see MAV_CMD_DO_JUMP param2). - - This command may trigger a mission state-machine change on some systems: for example from MISSION_STATE_NOT_STARTED or MISSION_STATE_PAUSED to MISSION_STATE_ACTIVE. - If the system is in mission mode, on those systems this command might therefore start, restart or resume the mission. - If the system is not in mission mode this command must not trigger a switch to mission mode. - - The mission may be "reset" using param2. - Resetting sets jump counters to initial values (to reset counters without changing the current mission item set the param1 to `-1`). - Resetting also explicitly changes a mission state of MISSION_STATE_COMPLETE to MISSION_STATE_PAUSED or MISSION_STATE_ACTIVE, potentially allowing it to resume when it is (next) in a mission mode. - - The command will ACK with MAV_RESULT_FAILED if the sequence number is out of range (including if there is no mission item). - - Mission sequence value to set. -1 for the current mission item (use to reset mission without changing current mission item). - Resets mission. 1: true, 0: false. Resets jump counters to initial values and changes mission state "completed" to be "active" or "paused". - Empty - Empty - Empty - Empty - Empty - - - NOP - This command is only used to mark the upper limit of the DO commands in the enumeration - Empty - Empty - Empty - Empty - Empty - Empty - Empty - - - Trigger calibration. This command will be only accepted if in pre-flight mode. Except for Temperature Calibration, only one sensor should be set in a single message and all others should be zero. - 1: gyro calibration, 3: gyro temperature calibration - 1: magnetometer calibration - 1: ground pressure calibration - 1: radio RC calibration, 2: RC trim calibration - 1: accelerometer calibration, 2: board level calibration, 3: accelerometer temperature calibration, 4: simple accelerometer calibration - 1: APM: compass/motor interference calibration (PX4: airspeed calibration, deprecated), 2: airspeed calibration - 1: ESC calibration, 3: barometer temperature calibration - - - Set sensor offsets. This command will be only accepted if in pre-flight mode. - Sensor to adjust the offsets for: 0: gyros, 1: accelerometer, 2: magnetometer, 3: barometer, 4: optical flow, 5: second magnetometer, 6: third magnetometer - X axis offset (or generic dimension 1), in the sensor's raw units - Y axis offset (or generic dimension 2), in the sensor's raw units - Z axis offset (or generic dimension 3), in the sensor's raw units - Generic dimension 4, in the sensor's raw units - Generic dimension 5, in the sensor's raw units - Generic dimension 6, in the sensor's raw units - - - Trigger UAVCAN configuration (actuator ID assignment and direction mapping). Note that this maps to the legacy UAVCAN v0 function UAVCAN_ENUMERATE, which is intended to be executed just once during initial vehicle configuration (it is not a normal pre-flight command and has been poorly named). - 1: Trigger actuator ID assignment and direction mapping. 0: Cancel command. - Reserved - Reserved - Reserved - Reserved - Reserved - Reserved - - - Request storage of different parameter values and logs. This command will be only accepted if in pre-flight mode. - Action to perform on the persistent parameter storage - Action to perform on the persistent mission storage - Onboard logging: 0: Ignore, 1: Start default rate logging, -1: Stop logging, > 1: logging rate (e.g. set to 1000 for 1000 Hz logging) - Reserved - Empty - Empty - Empty - - - Request the reboot or shutdown of system components. - 0: Do nothing for autopilot, 1: Reboot autopilot, 2: Shutdown autopilot, 3: Reboot autopilot and keep it in the bootloader until upgraded. - 0: Do nothing for onboard computer, 1: Reboot onboard computer, 2: Shutdown onboard computer, 3: Reboot onboard computer and keep it in the bootloader until upgraded. - 0: Do nothing for component, 1: Reboot component, 2: Shutdown component, 3: Reboot component and keep it in the bootloader until upgraded - MAVLink Component ID targeted in param3 (0 for all components). - Reserved (set to 0) - Reserved (set to 0) - WIP: ID (e.g. camera ID -1 for all IDs) - - - - Override current mission with command to pause mission, pause mission and move to position, continue/resume mission. When param 1 indicates that the mission is paused (MAV_GOTO_DO_HOLD), param 2 defines whether it holds in place or moves to another position. - MAV_GOTO_DO_HOLD: pause mission and either hold or move to specified position (depending on param2), MAV_GOTO_DO_CONTINUE: resume mission. - MAV_GOTO_HOLD_AT_CURRENT_POSITION: hold at current position, MAV_GOTO_HOLD_AT_SPECIFIED_POSITION: hold at specified position. - Coordinate frame of hold point. - Desired yaw angle. - Latitude/X position. - Longitude/Y position. - Altitude/Z position. - - - Mission command to set a Camera Auto Mount Pivoting Oblique Survey (Replaces CAM_TRIGG_DIST for this purpose). The camera is triggered each time this distance is exceeded, then the mount moves to the next position. Params 4~6 set-up the angle limits and number of positions for oblique survey, where mount-enabled vehicles automatically roll the camera between shots to emulate an oblique camera setup (providing an increased HFOV). This command can also be used to set the shutter integration time for the camera. - Camera trigger distance. 0 to stop triggering. - Camera shutter integration time. 0 to ignore - The minimum interval in which the camera is capable of taking subsequent pictures repeatedly. 0 to ignore. - Total number of roll positions at which the camera will capture photos (images captures spread evenly across the limits defined by param5). - Angle limits that the camera can be rolled to left and right of center. - Fixed pitch angle that the camera will hold in oblique mode if the mount is actuated in the pitch axis. - Empty - - - start running a mission - first_item: the first mission item to run - last_item: the last mission item to run (after this item is run, the mission ends) - - - Actuator testing command. This is similar to MAV_CMD_DO_MOTOR_TEST but operates on the level of output functions, i.e. it is possible to test Motor1 independent from which output it is configured on. Autopilots typically refuse this command while armed. - Output value: 1 means maximum positive output, 0 to center servos or minimum motor thrust (expected to spin), -1 for maximum negative (if not supported by the motors, i.e. motor is not reversible, smaller than 0 maps to NaN). And NaN maps to disarmed (stop the motors). - Timeout after which the test command expires and the output is restored to the previous value. A timeout has to be set for safety reasons. A timeout of 0 means to restore the previous value immediately. - - - Actuator Output function - - - - - Actuator configuration command. - Actuator configuration action - - - - Actuator Output function - - - - - Arms / Disarms a component - 0: disarm, 1: arm - 0: arm-disarm unless prevented by safety checks (i.e. when landed), 21196: force arming/disarming (e.g. allow arming to override preflight checks and disarming in flight) - - - Instructs a target system to run pre-arm checks. - This allows preflight checks to be run on demand, which may be useful on systems that normally run them at low rate, or which do not trigger checks when the armable state might have changed. - This command should return MAV_RESULT_ACCEPTED if it will run the checks. - The results of the checks are usually then reported in SYS_STATUS messages (this is system-specific). - The command should return MAV_RESULT_TEMPORARILY_REJECTED if the system is already armed. - - - - - - Turns illuminators ON/OFF. An illuminator is a light source that is used for lighting up dark areas external to the sytstem: e.g. a torch or searchlight (as opposed to a light source for illuminating the system itself, e.g. an indicator light). - 0: Illuminators OFF, 1: Illuminators ON - - - - Request the home position from the vehicle. - The vehicle will ACK the command and then emit the HOME_POSITION message. - Reserved - Reserved - Reserved - Reserved - Reserved - Reserved - Reserved - - - Inject artificial failure for testing purposes. Note that autopilots should implement an additional protection before accepting this command such as a specific param setting. - The unit which is affected by the failure. - The type how the failure manifests itself. - Instance affected by failure (0 to signal all). - - - Starts receiver pairing. - 0:Spektrum. - RC type. - - - - - Request the interval between messages for a particular MAVLink message ID. - The receiver should ACK the command and then emit its response in a MESSAGE_INTERVAL message. - - The MAVLink message ID - - - Set the interval between messages for a particular MAVLink message ID. This interface replaces REQUEST_DATA_STREAM. - The MAVLink message ID - The interval between two messages. -1: disable. 0: request default rate (which may be zero). - Target address of message stream (if message has target address fields). 0: Flight-stack default (recommended), 1: address of requestor, 2: broadcast. - - - Request the target system(s) emit a single instance of a specified message (i.e. a "one-shot" version of MAV_CMD_SET_MESSAGE_INTERVAL). - The MAVLink message ID of the requested message. - Use for index ID, if required. Otherwise, the use of this parameter (if any) must be defined in the requested message. By default assumed not used (0). - The use of this parameter (if any), must be defined in the requested message. By default assumed not used (0). - The use of this parameter (if any), must be defined in the requested message. By default assumed not used (0). - The use of this parameter (if any), must be defined in the requested message. By default assumed not used (0). - The use of this parameter (if any), must be defined in the requested message. By default assumed not used (0). - Target address for requested message (if message has target address fields). 0: Flight-stack default, 1: address of requestor, 2: broadcast. - - - - Request MAVLink protocol version compatibility. All receivers should ACK the command and then emit their capabilities in an PROTOCOL_VERSION message - 1: Request supported protocol versions by all nodes on the network - Reserved (all remaining params) - - - - Request autopilot capabilities. The receiver should ACK the command and then emit its capabilities in an AUTOPILOT_VERSION message - 1: Request autopilot version - Reserved (all remaining params) - - - - Request camera information (CAMERA_INFORMATION). - 0: No action 1: Request camera capabilities - Reserved (all remaining params) - - - - Request camera settings (CAMERA_SETTINGS). - 0: No Action 1: Request camera settings - Reserved (all remaining params) - - - - Request storage information (STORAGE_INFORMATION). Use the command's target_component to target a specific component's storage. - Storage ID (0 for all, 1 for first, 2 for second, etc.) - 0: No Action 1: Request storage information - Reserved (all remaining params) - - - Format a storage medium. Once format is complete, a STORAGE_INFORMATION message is sent. Use the command's target_component to target a specific component's storage. - Storage ID (1 for first, 2 for second, etc.) - Format storage (and reset image log). 0: No action 1: Format storage - Reset Image Log (without formatting storage medium). This will reset CAMERA_CAPTURE_STATUS.image_count and CAMERA_IMAGE_CAPTURED.image_index. 0: No action 1: Reset Image Log - Reserved (all remaining params) - - - - Request camera capture status (CAMERA_CAPTURE_STATUS) - 0: No Action 1: Request camera capture status - Reserved (all remaining params) - - - - Request flight information (FLIGHT_INFORMATION) - 1: Request flight information - Reserved (all remaining params) - - - Reset all camera settings to Factory Default - 0: No Action 1: Reset all settings - Reserved (all remaining params) - - - Set camera running mode. Use NaN for reserved values. GCS will send a MAV_CMD_REQUEST_VIDEO_STREAM_STATUS command after a mode change if the camera supports video streaming. - Reserved (Set to 0) - Camera mode - - - - - - Set camera zoom. Camera must respond with a CAMERA_SETTINGS message (on success). - Zoom type - Zoom value. The range of valid values depend on the zoom type. - - - - - - Set camera focus. Camera must respond with a CAMERA_SETTINGS message (on success). - Focus type - Focus value - - - - - - Set that a particular storage is the preferred location for saving photos, videos, and/or other media (e.g. to set that an SD card is used for storing videos). - There can only be one preferred save location for each particular media type: setting a media usage flag will clear/reset that same flag if set on any other storage. - If no flag is set the system should use its default storage. - A target system can choose to always use default storage, in which case it should ACK the command with MAV_RESULT_UNSUPPORTED. - A target system can choose to not allow a particular storage to be set as preferred storage, in which case it should ACK the command with MAV_RESULT_DENIED. - Storage ID (1 for first, 2 for second, etc.) - Usage flags - - - Tagged jump target. Can be jumped to with MAV_CMD_DO_JUMP_TAG. - Tag. - - - Jump to the matching tag in the mission list. Repeat this action for the specified number of times. A mission should contain a single matching tag for each jump. If this is not the case then a jump to a missing tag should complete the mission, and a jump where there are multiple matching tags should always select the one with the lowest mission sequence number. - Target tag to jump to. - Repeat count. - - - - Set gimbal manager pitch/yaw setpoints (low rate command). It is possible to set combinations of the values below. E.g. an angle as well as a desired angular rate can be used to get to this angle at a certain angular rate, or an angular rate only will result in continuous turning. NaN is to be used to signal unset. Note: only the gimbal manager will react to this command - it will be ignored by a gimbal device. Use GIMBAL_MANAGER_SET_PITCHYAW if you need to stream pitch/yaw setpoints at higher rate. - Pitch angle (positive to pitch up, relative to vehicle for FOLLOW mode, relative to world horizon for LOCK mode). - Yaw angle (positive to yaw to the right, relative to vehicle for FOLLOW mode, absolute to North for LOCK mode). - Pitch rate (positive to pitch up). - Yaw rate (positive to yaw to the right). - Gimbal manager flags to use. - Component ID of gimbal device to address (or 1-6 for non-MAVLink gimbal), 0 for all gimbal device components. Send command multiple times for more than one gimbal (but not all gimbals). - - - Gimbal configuration to set which sysid/compid is in primary and secondary control. - Sysid for primary control (0: no one in control, -1: leave unchanged, -2: set itself in control (for missions where the own sysid is still unknown), -3: remove control if currently in control). - Compid for primary control (0: no one in control, -1: leave unchanged, -2: set itself in control (for missions where the own sysid is still unknown), -3: remove control if currently in control). - Sysid for secondary control (0: no one in control, -1: leave unchanged, -2: set itself in control (for missions where the own sysid is still unknown), -3: remove control if currently in control). - Compid for secondary control (0: no one in control, -1: leave unchanged, -2: set itself in control (for missions where the own sysid is still unknown), -3: remove control if currently in control). - Component ID of gimbal device to address (or 1-6 for non-MAVLink gimbal), 0 for all gimbal device components. Send command multiple times for more than one gimbal (but not all gimbals). - - - Start image capture sequence. Sends CAMERA_IMAGE_CAPTURED after each capture. Use NaN for reserved values. - Reserved (Set to 0) - Desired elapsed time between two consecutive pictures (in seconds). Minimum values depend on hardware (typically greater than 2 seconds). - Total number of images to capture. 0 to capture forever/until MAV_CMD_IMAGE_STOP_CAPTURE. - Capture sequence number starting from 1. This is only valid for single-capture (param3 == 1), otherwise set to 0. Increment the capture ID for each capture command to prevent double captures when a command is re-transmitted. - - - - - - Stop image capture sequence Use NaN for reserved values. - Reserved (Set to 0) - - - - - - - - - - Re-request a CAMERA_IMAGE_CAPTURED message. - Sequence number for missing CAMERA_IMAGE_CAPTURED message - - - - - - - - - Enable or disable on-board camera triggering system. - Trigger enable/disable (0 for disable, 1 for start), -1 to ignore - 1 to reset the trigger sequence, -1 or 0 to ignore - 1 to pause triggering, but without switching the camera off or retracting it. -1 to ignore - - - If the camera supports point visual tracking (CAMERA_CAP_FLAGS_HAS_TRACKING_POINT is set), this command allows to initiate the tracking. - Point to track x value (normalized 0..1, 0 is left, 1 is right). - Point to track y value (normalized 0..1, 0 is top, 1 is bottom). - Point radius (normalized 0..1, 0 is image left, 1 is image right). - - - If the camera supports rectangle visual tracking (CAMERA_CAP_FLAGS_HAS_TRACKING_RECTANGLE is set), this command allows to initiate the tracking. - Top left corner of rectangle x value (normalized 0..1, 0 is left, 1 is right). - Top left corner of rectangle y value (normalized 0..1, 0 is top, 1 is bottom). - Bottom right corner of rectangle x value (normalized 0..1, 0 is left, 1 is right). - Bottom right corner of rectangle y value (normalized 0..1, 0 is top, 1 is bottom). - - - Stops ongoing tracking. - - - Starts video capture (recording). - Video Stream ID (0 for all streams) - Frequency CAMERA_CAPTURE_STATUS messages should be sent while recording (0 for no messages, otherwise frequency) - - - - - - - - Stop the current video capture (recording). - Video Stream ID (0 for all streams) - - - - - - - - - Start video streaming - Video Stream ID (0 for all streams, 1 for first, 2 for second, etc.) - - - Stop the given video stream - Video Stream ID (0 for all streams, 1 for first, 2 for second, etc.) - - - - Request video stream information (VIDEO_STREAM_INFORMATION) - Video Stream ID (0 for all streams, 1 for first, 2 for second, etc.) - - - - Request video stream status (VIDEO_STREAM_STATUS) - Video Stream ID (0 for all streams, 1 for first, 2 for second, etc.) - - - Request to start streaming logging data over MAVLink (see also LOGGING_DATA message) - Format: 0: ULog - Reserved (set to 0) - Reserved (set to 0) - Reserved (set to 0) - Reserved (set to 0) - Reserved (set to 0) - Reserved (set to 0) - - - Request to stop streaming log data over MAVLink - Reserved (set to 0) - Reserved (set to 0) - Reserved (set to 0) - Reserved (set to 0) - Reserved (set to 0) - Reserved (set to 0) - Reserved (set to 0) - - - - Landing gear ID (default: 0, -1 for all) - Landing gear position (Down: 0, Up: 1, NaN for no change) - - - - - - - - Request to start/stop transmitting over the high latency telemetry - Control transmission over high latency telemetry (0: stop, 1: start) - Empty - Empty - Empty - Empty - Empty - Empty - - - Create a panorama at the current position - Viewing angle horizontal of the panorama (+- 0.5 the total angle) - Viewing angle vertical of panorama. - Speed of the horizontal rotation. - Speed of the vertical rotation. - - - Request VTOL transition - The target VTOL state. For normal transitions, only MAV_VTOL_STATE_MC and MAV_VTOL_STATE_FW can be used. - Force immediate transition to the specified MAV_VTOL_STATE. 1: Force immediate, 0: normal transition. Can be used, for example, to trigger an emergency "Quadchute". Caution: Can be dangerous/damage vehicle, depending on autopilot implementation of this command. - - - Request authorization to arm the vehicle to a external entity, the arm authorizer is responsible to request all data that is needs from the vehicle before authorize or deny the request. - If approved the COMMAND_ACK message progress field should be set with period of time that this authorization is valid in seconds. - If the authorization is denied COMMAND_ACK.result_param2 should be set with one of the reasons in ARM_AUTH_DENIED_REASON. - - Vehicle system id, this way ground station can request arm authorization on behalf of any vehicle - - - This command sets the submode to standard guided when vehicle is in guided mode. The vehicle holds position and altitude and the user can input the desired velocities along all three axes. - - - - This command sets submode circle when vehicle is in guided mode. Vehicle flies along a circle facing the center of the circle. The user can input the velocity along the circle and change the radius. If no input is given the vehicle will hold position. - - Radius of desired circle in CIRCLE_MODE - User defined - User defined - User defined - Target latitude of center of circle in CIRCLE_MODE - Target longitude of center of circle in CIRCLE_MODE - - - - - Delay mission state machine until gate has been reached. - Geometry: 0: orthogonal to path between previous and next waypoint. - Altitude: 0: ignore altitude - Empty - Empty - Latitude - Longitude - Altitude - - - Fence return point (there can only be one such point in a geofence definition). If rally points are supported they should be used instead. - Reserved - Reserved - Reserved - Reserved - Latitude - Longitude - Altitude - - - Fence vertex for an inclusion polygon (the polygon must not be self-intersecting). The vehicle must stay within this area. Minimum of 3 vertices required. - - Polygon vertex count - Vehicle must be inside ALL inclusion zones in a single group, vehicle must be inside at least one group, must be the same for all points in each polygon - Reserved - Reserved - Latitude - Longitude - Reserved - - - Fence vertex for an exclusion polygon (the polygon must not be self-intersecting). The vehicle must stay outside this area. Minimum of 3 vertices required. - - Polygon vertex count - Reserved - Reserved - Reserved - Latitude - Longitude - Reserved - - - Circular fence area. The vehicle must stay inside this area. - - Radius. - Vehicle must be inside ALL inclusion zones in a single group, vehicle must be inside at least one group - Reserved - Reserved - Latitude - Longitude - Reserved - - - Circular fence area. The vehicle must stay outside this area. - - Radius. - Reserved - Reserved - Reserved - Latitude - Longitude - Reserved - - - - Rally point. You can have multiple rally points defined. - - Reserved - Reserved - Reserved - Reserved - Latitude - Longitude - Altitude - - - - - Commands the vehicle to respond with a sequence of messages UAVCAN_NODE_INFO, one message per every UAVCAN node that is online. Note that some of the response messages can be lost, which the receiver can detect easily by checking whether every received UAVCAN_NODE_STATUS has a matching message UAVCAN_NODE_INFO received earlier; if not, this command should be sent again in order to request re-transmission of the node information messages. - Reserved (set to 0) - Reserved (set to 0) - Reserved (set to 0) - Reserved (set to 0) - Reserved (set to 0) - Reserved (set to 0) - Reserved (set to 0) - - - - Trigger the start of an ADSB-out IDENT. This should only be used when requested to do so by an Air Traffic Controller in controlled airspace. This starts the IDENT which is then typically held for 18 seconds by the hardware per the Mode A, C, and S transponder spec. - Reserved (set to 0) - Reserved (set to 0) - Reserved (set to 0) - Reserved (set to 0) - Reserved (set to 0) - Reserved (set to 0) - Reserved (set to 0) - - - - - - Deploy payload on a Lat / Lon / Alt position. This includes the navigation to reach the required release position and velocity. - Operation mode. 0: prepare single payload deploy (overwriting previous requests), but do not execute it. 1: execute payload deploy immediately (rejecting further deploy commands during execution, but allowing abort). 2: add payload deploy to existing deployment list. - Desired approach vector in compass heading. A negative value indicates the system can define the approach vector at will. - Desired ground speed at release time. This can be overridden by the airframe in case it needs to meet minimum airspeed. A negative value indicates the system can define the ground speed at will. - Minimum altitude clearance to the release position. A negative value indicates the system can define the clearance at will. - Latitude. - Longitude. - Altitude (MSL) - - - - Control the payload deployment. - Operation mode. 0: Abort deployment, continue normal mission. 1: switch to payload deployment mode. 100: delete first payload deployment request. 101: delete all payload deployment requests. - Reserved - Reserved - Reserved - Reserved - Reserved - Reserved - - - - Magnetometer calibration based on provided known yaw. This allows for fast calibration using WMM field tables in the vehicle, given only the known yaw of the vehicle. If Latitude and longitude are both zero then use the current vehicle location. - Yaw of vehicle in earth frame. - CompassMask, 0 for all. - Latitude. - Longitude. - Empty. - Empty. - Empty. - - - Command to operate winch. - Winch instance number. - Action to perform. - Length of line to release (negative to wind). - Release rate (negative to wind). - Empty. - Empty. - Empty. - - - - - User defined waypoint item. Ground Station will show the Vehicle as flying through this item. - User defined - User defined - User defined - User defined - Latitude unscaled - Longitude unscaled - Altitude (MSL) - - - User defined waypoint item. Ground Station will show the Vehicle as flying through this item. - User defined - User defined - User defined - User defined - Latitude unscaled - Longitude unscaled - Altitude (MSL) - - - User defined waypoint item. Ground Station will show the Vehicle as flying through this item. - User defined - User defined - User defined - User defined - Latitude unscaled - Longitude unscaled - Altitude (MSL) - - - User defined waypoint item. Ground Station will show the Vehicle as flying through this item. - User defined - User defined - User defined - User defined - Latitude unscaled - Longitude unscaled - Altitude (MSL) - - - User defined waypoint item. Ground Station will show the Vehicle as flying through this item. - User defined - User defined - User defined - User defined - Latitude unscaled - Longitude unscaled - Altitude (MSL) - - - User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item. - User defined - User defined - User defined - User defined - Latitude unscaled - Longitude unscaled - Altitude (MSL) - - - User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item. - User defined - User defined - User defined - User defined - Latitude unscaled - Longitude unscaled - Altitude (MSL) - - - User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item. - User defined - User defined - User defined - User defined - Latitude unscaled - Longitude unscaled - Altitude (MSL) - - - User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item. - User defined - User defined - User defined - User defined - Latitude unscaled - Longitude unscaled - Altitude (MSL) - - - User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item. - User defined - User defined - User defined - User defined - Latitude unscaled - Longitude unscaled - Altitude (MSL) - - - User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item. - User defined - User defined - User defined - User defined - User defined - User defined - User defined - - - User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item. - User defined - User defined - User defined - User defined - User defined - User defined - User defined - - - User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item. - User defined - User defined - User defined - User defined - User defined - User defined - User defined - - - User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item. - User defined - User defined - User defined - User defined - User defined - User defined - User defined - - - User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item. - User defined - User defined - User defined - User defined - User defined - User defined - User defined - - - - Request forwarding of CAN packets from the given CAN bus to this component. CAN Frames are sent using CAN_FRAME and CANFD_FRAME messages - Bus number (0 to disable forwarding, 1 for first bus, 2 for 2nd bus, 3 for 3rd bus). - Empty. - Empty. - Empty. - Empty. - Empty. - Empty. - - - - - A data stream is not a fixed set of messages, but rather a - recommendation to the autopilot software. Individual autopilots may or may not obey - the recommended messages. - - Enable all data streams - - - Enable IMU_RAW, GPS_RAW, GPS_STATUS packets. - - - Enable GPS_STATUS, CONTROL_STATUS, AUX_STATUS - - - Enable RC_CHANNELS_SCALED, RC_CHANNELS_RAW, SERVO_OUTPUT_RAW - - - Enable ATTITUDE_CONTROLLER_OUTPUT, POSITION_CONTROLLER_OUTPUT, NAV_CONTROLLER_OUTPUT. - - - Enable LOCAL_POSITION, GLOBAL_POSITION_INT messages. - - - Dependent on the autopilot - - - Dependent on the autopilot - - - Dependent on the autopilot - - - - - The ROI (region of interest) for the vehicle. This can be - be used by the vehicle for camera/vehicle attitude alignment (see - MAV_CMD_NAV_ROI). - - No region of interest. - - - Point toward next waypoint, with optional pitch/roll/yaw offset. - - - Point toward given waypoint. - - - Point toward fixed location. - - - Point toward of given id. - - - - Specifies the datatype of a MAVLink parameter. - - 8-bit unsigned integer - - - 8-bit signed integer - - - 16-bit unsigned integer - - - 16-bit signed integer - - - 32-bit unsigned integer - - - 32-bit signed integer - - - 64-bit unsigned integer - - - 64-bit signed integer - - - 32-bit floating-point - - - 64-bit floating-point - - - - Specifies the datatype of a MAVLink extended parameter. - - 8-bit unsigned integer - - - 8-bit signed integer - - - 16-bit unsigned integer - - - 16-bit signed integer - - - 32-bit unsigned integer - - - 32-bit signed integer - - - 64-bit unsigned integer - - - 64-bit signed integer - - - 32-bit floating-point - - - 64-bit floating-point - - - Custom Type - - - - Result from a MAVLink command (MAV_CMD) - - Command is valid (is supported and has valid parameters), and was executed. - - - Command is valid, but cannot be executed at this time. This is used to indicate a problem that should be fixed just by waiting (e.g. a state machine is busy, can't arm because have not got GPS lock, etc.). Retrying later should work. - - - Command is invalid (is supported but has invalid parameters). Retrying same command and parameters will not work. - - - Command is not supported (unknown). - - - Command is valid, but execution has failed. This is used to indicate any non-temporary or unexpected problem, i.e. any problem that must be fixed before the command can succeed/be retried. For example, attempting to write a file when out of memory, attempting to arm when sensors are not calibrated, etc. - - - Command is valid and is being executed. This will be followed by further progress updates, i.e. the component may send further COMMAND_ACK messages with result MAV_RESULT_IN_PROGRESS (at a rate decided by the implementation), and must terminate by sending a COMMAND_ACK message with final result of the operation. The COMMAND_ACK.progress field can be used to indicate the progress of the operation. - - - Command has been cancelled (as a result of receiving a COMMAND_CANCEL message). - - - Command is valid, but it is only accepted when sent as a COMMAND_LONG (as it has float values for params 5 and 6). - - - Command is valid, but it is only accepted when sent as a COMMAND_INT (as it encodes a location in params 5, 6 and 7, and hence requires a reference MAV_FRAME). - - - Command is invalid because a frame is required and the specified frame is not supported. - - - - Result of mission operation (in a MISSION_ACK message). - - mission accepted OK - - - Generic error / not accepting mission commands at all right now. - - - Coordinate frame is not supported. - - - Command is not supported. - - - Mission items exceed storage space. - - - One of the parameters has an invalid value. - - - param1 has an invalid value. - - - param2 has an invalid value. - - - param3 has an invalid value. - - - param4 has an invalid value. - - - x / param5 has an invalid value. - - - y / param6 has an invalid value. - - - z / param7 has an invalid value. - - - Mission item received out of sequence - - - Not accepting any mission commands from this communication partner. - - - Current mission operation cancelled (e.g. mission upload, mission download). - - - - Indicates the severity level, generally used for status messages to indicate their relative urgency. Based on RFC-5424 using expanded definitions at: http://www.kiwisyslog.com/kb/info:-syslog-message-levels/. - - System is unusable. This is a "panic" condition. - - - Action should be taken immediately. Indicates error in non-critical systems. - - - Action must be taken immediately. Indicates failure in a primary system. - - - Indicates an error in secondary/redundant systems. - - - Indicates about a possible future error if this is not resolved within a given timeframe. Example would be a low battery warning. - - - An unusual event has occurred, though not an error condition. This should be investigated for the root cause. - - - Normal operational messages. Useful for logging. No action is required for these messages. - - - Useful non-operational messages that can assist in debugging. These should not occur during normal operation. - - - - Power supply status flags (bitmask) - - main brick power supply valid - - - main servo power supply valid for FMU - - - USB power is connected - - - peripheral supply is in over-current state - - - hi-power peripheral supply is in over-current state - - - Power status has changed since boot - - - - SERIAL_CONTROL device types - - First telemetry port - - - Second telemetry port - - - First GPS port - - - Second GPS port - - - system shell - - - SERIAL0 - - - SERIAL1 - - - SERIAL2 - - - SERIAL3 - - - SERIAL4 - - - SERIAL5 - - - SERIAL6 - - - SERIAL7 - - - SERIAL8 - - - SERIAL9 - - - - SERIAL_CONTROL flags (bitmask) - - Set if this is a reply - - - Set if the sender wants the receiver to send a response as another SERIAL_CONTROL message - - - Set if access to the serial port should be removed from whatever driver is currently using it, giving exclusive access to the SERIAL_CONTROL protocol. The port can be handed back by sending a request without this flag set - - - Block on writes to the serial port - - - Send multiple replies until port is drained - - - - Enumeration of distance sensor types - - Laser rangefinder, e.g. LightWare SF02/F or PulsedLight units - - - Ultrasound rangefinder, e.g. MaxBotix units - - - Infrared rangefinder, e.g. Sharp units - - - Radar type, e.g. uLanding units - - - Broken or unknown type, e.g. analog units - - - - Enumeration of sensor orientation, according to its rotations - - Roll: 0, Pitch: 0, Yaw: 0 - - - Roll: 0, Pitch: 0, Yaw: 45 - - - Roll: 0, Pitch: 0, Yaw: 90 - - - Roll: 0, Pitch: 0, Yaw: 135 - - - Roll: 0, Pitch: 0, Yaw: 180 - - - Roll: 0, Pitch: 0, Yaw: 225 - - - Roll: 0, Pitch: 0, Yaw: 270 - - - Roll: 0, Pitch: 0, Yaw: 315 - - - Roll: 180, Pitch: 0, Yaw: 0 - - - Roll: 180, Pitch: 0, Yaw: 45 - - - Roll: 180, Pitch: 0, Yaw: 90 - - - Roll: 180, Pitch: 0, Yaw: 135 - - - Roll: 0, Pitch: 180, Yaw: 0 - - - Roll: 180, Pitch: 0, Yaw: 225 - - - Roll: 180, Pitch: 0, Yaw: 270 - - - Roll: 180, Pitch: 0, Yaw: 315 - - - Roll: 90, Pitch: 0, Yaw: 0 - - - Roll: 90, Pitch: 0, Yaw: 45 - - - Roll: 90, Pitch: 0, Yaw: 90 - - - Roll: 90, Pitch: 0, Yaw: 135 - - - Roll: 270, Pitch: 0, Yaw: 0 - - - Roll: 270, Pitch: 0, Yaw: 45 - - - Roll: 270, Pitch: 0, Yaw: 90 - - - Roll: 270, Pitch: 0, Yaw: 135 - - - Roll: 0, Pitch: 90, Yaw: 0 - - - Roll: 0, Pitch: 270, Yaw: 0 - - - Roll: 0, Pitch: 180, Yaw: 90 - - - Roll: 0, Pitch: 180, Yaw: 270 - - - Roll: 90, Pitch: 90, Yaw: 0 - - - Roll: 180, Pitch: 90, Yaw: 0 - - - Roll: 270, Pitch: 90, Yaw: 0 - - - Roll: 90, Pitch: 180, Yaw: 0 - - - Roll: 270, Pitch: 180, Yaw: 0 - - - Roll: 90, Pitch: 270, Yaw: 0 - - - Roll: 180, Pitch: 270, Yaw: 0 - - - Roll: 270, Pitch: 270, Yaw: 0 - - - Roll: 90, Pitch: 180, Yaw: 90 - - - Roll: 90, Pitch: 0, Yaw: 270 - - - Roll: 90, Pitch: 68, Yaw: 293 - - - Pitch: 315 - - - Roll: 90, Pitch: 315 - - - Custom orientation - - - - Bitmask of (optional) autopilot capabilities (64 bit). If a bit is set, the autopilot supports this capability. - - Autopilot supports the MISSION_ITEM float message type. - Note that MISSION_ITEM is deprecated, and autopilots should use MISSION_INT instead. - - - - - Autopilot supports the new param float message type. - - - Autopilot supports MISSION_ITEM_INT scaled integer message type. - Note that this flag must always be set if missions are supported, because missions must always use MISSION_ITEM_INT (rather than MISSION_ITEM, which is deprecated). - - - - Autopilot supports COMMAND_INT scaled integer message type. - - - Parameter protocol uses byte-wise encoding of parameter values into param_value (float) fields: https://mavlink.io/en/services/parameter.html#parameter-encoding. - Note that either this flag or MAV_PROTOCOL_CAPABILITY_PARAM_ENCODE_C_CAST should be set if the parameter protocol is supported. - - - - Autopilot supports the File Transfer Protocol v1: https://mavlink.io/en/services/ftp.html. - - - Autopilot supports commanding attitude offboard. - - - Autopilot supports commanding position and velocity targets in local NED frame. - - - Autopilot supports commanding position and velocity targets in global scaled integers. - - - Autopilot supports terrain protocol / data handling. - - - Reserved for future use. - - - Autopilot supports the MAV_CMD_DO_FLIGHTTERMINATION command (flight termination). - - - Autopilot supports onboard compass calibration. - - - Autopilot supports MAVLink version 2. - - - Autopilot supports mission fence protocol. - - - Autopilot supports mission rally point protocol. - - - Reserved for future use. - - - Parameter protocol uses C-cast of parameter values to set the param_value (float) fields: https://mavlink.io/en/services/parameter.html#parameter-encoding. - Note that either this flag or MAV_PROTOCOL_CAPABILITY_PARAM_ENCODE_BYTEWISE should be set if the parameter protocol is supported. - - - - - Type of mission items being requested/sent in mission protocol. - - Items are mission commands for main mission. - - - Specifies GeoFence area(s). Items are MAV_CMD_NAV_FENCE_ GeoFence items. - - - Specifies the rally points for the vehicle. Rally points are alternative RTL points. Items are MAV_CMD_NAV_RALLY_POINT rally point items. - - - Only used in MISSION_CLEAR_ALL to clear all mission types. - - - - Enumeration of estimator types - - Unknown type of the estimator. - - - This is a naive estimator without any real covariance feedback. - - - Computer vision based estimate. Might be up to scale. - - - Visual-inertial estimate. - - - Plain GPS estimate. - - - Estimator integrating GPS and inertial sensing. - - - Estimate from external motion capturing system. - - - Estimator based on lidar sensor input. - - - Estimator on autopilot. - - - - Enumeration of battery types - - Not specified. - - - Lithium polymer battery - - - Lithium-iron-phosphate battery - - - Lithium-ION battery - - - Nickel metal hydride battery - - - - Enumeration of battery functions - - Battery function is unknown - - - Battery supports all flight systems - - - Battery for the propulsion system - - - Avionics battery - - - Payload battery - - - - Enumeration for battery charge states. - - Low battery state is not provided - - - Battery is not in low state. Normal operation. - - - Battery state is low, warn and monitor close. - - - Battery state is critical, return or abort immediately. - - - Battery state is too low for ordinary abort sequence. Perform fastest possible emergency stop to prevent damage. - - - Battery failed, damage unavoidable. Possible causes (faults) are listed in MAV_BATTERY_FAULT. - - - Battery is diagnosed to be defective or an error occurred, usage is discouraged / prohibited. Possible causes (faults) are listed in MAV_BATTERY_FAULT. - - - Battery is charging. - - - - Battery mode. Note, the normal operation mode (i.e. when flying) should be reported as MAV_BATTERY_MODE_UNKNOWN to allow message trimming in normal flight. - - Battery mode not supported/unknown battery mode/normal operation. - - - Battery is auto discharging (towards storage level). - - - Battery in hot-swap mode (current limited to prevent spikes that might damage sensitive electrical circuits). - - - - Smart battery supply status/fault flags (bitmask) for health indication. The battery must also report either MAV_BATTERY_CHARGE_STATE_FAILED or MAV_BATTERY_CHARGE_STATE_UNHEALTHY if any of these are set. - - Battery has deep discharged. - - - Voltage spikes. - - - One or more cells have failed. Battery should also report MAV_BATTERY_CHARGE_STATE_FAILE (and should not be used). - - - Over-current fault. - - - Over-temperature fault. - - - Under-temperature fault. - - - Vehicle voltage is not compatible with this battery (batteries on same power rail should have similar voltage). - - - Battery firmware is not compatible with current autopilot firmware. - - - Battery is not compatible due to cell configuration (e.g. 5s1p when vehicle requires 6s). - - - - Flags to report status/failure cases for a power generator (used in GENERATOR_STATUS). Note that FAULTS are conditions that cause the generator to fail. Warnings are conditions that require attention before the next use (they indicate the system is not operating properly). - - Generator is off. - - - Generator is ready to start generating power. - - - Generator is generating power. - - - Generator is charging the batteries (generating enough power to charge and provide the load). - - - Generator is operating at a reduced maximum power. - - - Generator is providing the maximum output. - - - Generator is near the maximum operating temperature, cooling is insufficient. - - - Generator hit the maximum operating temperature and shutdown. - - - Power electronics are near the maximum operating temperature, cooling is insufficient. - - - Power electronics hit the maximum operating temperature and shutdown. - - - Power electronics experienced a fault and shutdown. - - - The power source supplying the generator failed e.g. mechanical generator stopped, tether is no longer providing power, solar cell is in shade, hydrogen reaction no longer happening. - - - Generator controller having communication problems. - - - Power electronic or generator cooling system error. - - - Generator controller power rail experienced a fault. - - - Generator controller exceeded the overcurrent threshold and shutdown to prevent damage. - - - Generator controller detected a high current going into the batteries and shutdown to prevent battery damage. - - - Generator controller exceeded it's overvoltage threshold and shutdown to prevent it exceeding the voltage rating. - - - Batteries are under voltage (generator will not start). - - - Generator start is inhibited by e.g. a safety switch. - - - Generator requires maintenance. - - - Generator is not ready to generate yet. - - - Generator is idle. - - - - Enumeration of VTOL states - - MAV is not configured as VTOL - - - VTOL is in transition from multicopter to fixed-wing - - - VTOL is in transition from fixed-wing to multicopter - - - VTOL is in multicopter state - - - VTOL is in fixed-wing state - - - - Enumeration of landed detector states - - MAV landed state is unknown - - - MAV is landed (on ground) - - - MAV is in air - - - MAV currently taking off - - - MAV currently landing - - - - Enumeration of the ADSB altimeter types - - Altitude reported from a Baro source using QNH reference - - - Altitude reported from a GNSS source - - - - ADSB classification for the type of vehicle emitting the transponder signal - - - - - - - - - - - - - - - - - - - - - - - These flags indicate status such as data validity of each data source. Set = data valid - - - - - - - - - - - - - Bitmap of options for the MAV_CMD_DO_REPOSITION - - The aircraft should immediately transition into guided. This should not be set for follow me applications - - - - - Flags in ESTIMATOR_STATUS message - - True if the attitude estimate is good - - - True if the horizontal velocity estimate is good - - - True if the vertical velocity estimate is good - - - True if the horizontal position (relative) estimate is good - - - True if the horizontal position (absolute) estimate is good - - - True if the vertical position (absolute) estimate is good - - - True if the vertical position (above ground) estimate is good - - - True if the EKF is in a constant position mode and is not using external measurements (eg GPS or optical flow) - - - True if the EKF has sufficient data to enter a mode that will provide a (relative) position estimate - - - True if the EKF has sufficient data to enter a mode that will provide a (absolute) position estimate - - - True if the EKF has detected a GPS glitch - - - True if the EKF has detected bad accelerometer data - - - - - Sequence that motors are tested when using MAV_CMD_DO_MOTOR_TEST. - - Default autopilot motor test method. - - - Motor numbers are specified as their index in a predefined vehicle-specific sequence. - - - Motor numbers are specified as the output as labeled on the board. - - - - - Defines how throttle value is represented in MAV_CMD_DO_MOTOR_TEST. - - Throttle as a percentage (0 ~ 100) - - - Throttle as an absolute PWM value (normally in range of 1000~2000). - - - Throttle pass-through from pilot's transmitter. - - - Per-motor compass calibration test. - - - - - - ignore altitude field - - - ignore hdop field - - - ignore vdop field - - - ignore horizontal velocity field (vn and ve) - - - ignore vertical velocity field (vd) - - - ignore speed accuracy field - - - ignore horizontal accuracy field - - - ignore vertical accuracy field - - - - Possible actions an aircraft can take to avoid a collision. - - Ignore any potential collisions - - - Report potential collision - - - Ascend or Descend to avoid threat - - - Move horizontally to avoid threat - - - Aircraft to move perpendicular to the collision's velocity vector - - - Aircraft to fly directly back to its launch point - - - Aircraft to stop in place - - - - Aircraft-rated danger from this threat. - - Not a threat - - - Craft is mildly concerned about this threat - - - Craft is panicking, and may take actions to avoid threat - - - - Source of information about this collision. - - ID field references ADSB_VEHICLE packets - - - ID field references MAVLink SRC ID - - - - Type of GPS fix - - No GPS connected - - - No position information, GPS is connected - - - 2D position - - - 3D position - - - DGPS/SBAS aided 3D position - - - RTK float, 3D position - - - RTK Fixed, 3D position - - - Static fixed, typically used for base stations - - - PPP, 3D position. - - - - RTK GPS baseline coordinate system, used for RTK corrections - - Earth-centered, Earth-fixed - - - RTK basestation centered, north, east, down - - - - Type of landing target - - Landing target signaled by light beacon (ex: IR-LOCK) - - - Landing target signaled by radio beacon (ex: ILS, NDB) - - - Landing target represented by a fiducial marker (ex: ARTag) - - - Landing target represented by a pre-defined visual shape/feature (ex: X-marker, H-marker, square) - - - - Direction of VTOL transition - - Respect the heading configuration of the vehicle. - - - Use the heading pointing towards the next waypoint. - - - Use the heading on takeoff (while sitting on the ground). - - - Use the specified heading in parameter 4. - - - Use the current heading when reaching takeoff altitude (potentially facing the wind when weather-vaning is active). - - - - Camera capability flags (Bitmap) - - Camera is able to record video - - - Camera is able to capture images - - - Camera has separate Video and Image/Photo modes (MAV_CMD_SET_CAMERA_MODE) - - - Camera can capture images while in video mode - - - Camera can capture videos while in Photo/Image mode - - - Camera has image survey mode (MAV_CMD_SET_CAMERA_MODE) - - - Camera has basic zoom control (MAV_CMD_SET_CAMERA_ZOOM) - - - Camera has basic focus control (MAV_CMD_SET_CAMERA_FOCUS) - - - Camera has video streaming capabilities (request VIDEO_STREAM_INFORMATION with MAV_CMD_REQUEST_MESSAGE for video streaming info) - - - Camera supports tracking of a point on the camera view. - - - Camera supports tracking of a selection rectangle on the camera view. - - - Camera supports tracking geo status (CAMERA_TRACKING_GEO_STATUS). - - - - Stream status flags (Bitmap) - - Stream is active (running) - - - Stream is thermal imaging - - - - Video stream types - - Stream is RTSP - - - Stream is RTP UDP (URI gives the port number) - - - Stream is MPEG on TCP - - - Stream is h.264 on MPEG TS (URI gives the port number) - - - - Camera tracking status flags - - Camera is not tracking - - - Camera is tracking - - - Camera tracking in error state - - - - Camera tracking modes - - Not tracking - - - Target is a point - - - Target is a rectangle - - - - Camera tracking target data (shows where tracked target is within image) - - No target data - - - Target data embedded in image data (proprietary) - - - Target data rendered in image - - - Target data within status message (Point or Rectangle) - - - - Zoom types for MAV_CMD_SET_CAMERA_ZOOM - - Zoom one step increment (-1 for wide, 1 for tele) - - - Continuous zoom up/down until stopped (-1 for wide, 1 for tele, 0 to stop zooming) - - - Zoom value as proportion of full camera range (a percentage value between 0.0 and 100.0) - - - Zoom value/variable focal length in millimetres. Note that there is no message to get the valid zoom range of the camera, so this can type can only be used for cameras where the zoom range is known (implying that this cannot reliably be used in a GCS for an arbitrary camera) - - - Zoom value as horizontal field of view in degrees. - - - - Focus types for MAV_CMD_SET_CAMERA_FOCUS - - Focus one step increment (-1 for focusing in, 1 for focusing out towards infinity). - - - Continuous focus up/down until stopped (-1 for focusing in, 1 for focusing out towards infinity, 0 to stop focusing) - - - Focus value as proportion of full camera focus range (a value between 0.0 and 100.0) - - - Focus value in metres. Note that there is no message to get the valid focus range of the camera, so this can type can only be used for cameras where the range is known (implying that this cannot reliably be used in a GCS for an arbitrary camera). - - - Focus automatically. - - - Single auto focus. Mainly used for still pictures. Usually abbreviated as AF-S. - - - Continuous auto focus. Mainly used for dynamic scenes. Abbreviated as AF-C. - - - - Result from PARAM_EXT_SET message (or a PARAM_SET within a transaction). - - Parameter value ACCEPTED and SET - - - Parameter value UNKNOWN/UNSUPPORTED - - - Parameter failed to set - - - Parameter value received but not yet set/accepted. A subsequent PARAM_ACK_TRANSACTION or PARAM_EXT_ACK with the final result will follow once operation is completed. This is returned immediately for parameters that take longer to set, indicating that the the parameter was received and does not need to be resent. - - - - Camera Modes. - - Camera is in image/photo capture mode. - - - Camera is in video capture mode. - - - Camera is in image survey capture mode. It allows for camera controller to do specific settings for surveys. - - - - - Not a specific reason - - - Authorizer will send the error as string to GCS - - - At least one waypoint have a invalid value - - - Timeout in the authorizer process(in case it depends on network) - - - Airspace of the mission in use by another vehicle, second result parameter can have the waypoint id that caused it to be denied. - - - Weather is not good to fly - - - - RC type - - Spektrum DSM2 - - - Spektrum DSMX - - - - Bitmap to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 9 is set the floats afx afy afz should be interpreted as force instead of acceleration. - - Ignore position x - - - Ignore position y - - - Ignore position z - - - Ignore velocity x - - - Ignore velocity y - - - Ignore velocity z - - - Ignore acceleration x - - - Ignore acceleration y - - - Ignore acceleration z - - - Use force instead of acceleration - - - Ignore yaw - - - Ignore yaw rate - - - - Bitmap to indicate which dimensions should be ignored by the vehicle: a value of 0b00000000 indicates that none of the setpoint dimensions should be ignored. - - Ignore body roll rate - - - Ignore body pitch rate - - - Ignore body yaw rate - - - Use 3D body thrust setpoint instead of throttle - - - Ignore throttle - - - Ignore attitude - - - - Airborne status of UAS. - - The flight state can't be determined. - - - UAS on ground. - - - UAS airborne. - - - UAS is in an emergency flight state. - - - UAS has no active controls. - - - - Flags for the global position report. - - The field time contains valid data. - - - The field uas_id contains valid data. - - - The fields lat, lon and h_acc contain valid data. - - - The fields alt and v_acc contain valid data. - - - The field relative_alt contains valid data. - - - The fields vx and vy contain valid data. - - - The field vz contains valid data. - - - The fields next_lat, next_lon and next_alt contain valid data. - - - - - These flags encode the cellular network status - - State unknown or not reportable. - - - Modem is unusable - - - Modem is being initialized - - - Modem is locked - - - Modem is not enabled and is powered down - - - Modem is currently transitioning to the CELLULAR_STATUS_FLAG_DISABLED state - - - Modem is currently transitioning to the CELLULAR_STATUS_FLAG_ENABLED state - - - Modem is enabled and powered on but not registered with a network provider and not available for data connections - - - Modem is searching for a network provider to register - - - Modem is registered with a network provider, and data connections and messaging may be available for use - - - Modem is disconnecting and deactivating the last active packet data bearer. This state will not be entered if more than one packet data bearer is active and one of the active bearers is deactivated - - - Modem is activating and connecting the first packet data bearer. Subsequent bearer activations when another bearer is already active do not cause this state to be entered - - - One or more packet data bearers is active and connected - - - - These flags are used to diagnose the failure state of CELLULAR_STATUS - - No error - - - Error state is unknown - - - SIM is required for the modem but missing - - - SIM is available, but not usable for connection - - - - Cellular network radio type - - - - - - - - Precision land modes (used in MAV_CMD_NAV_LAND). - - Normal (non-precision) landing. - - - Use precision landing if beacon detected when land command accepted, otherwise land normally. - - - Use precision landing, searching for beacon if not found when land command accepted (land normally if beacon cannot be found). - - - - - Parachute actions. Trigger release and enable/disable auto-release. - - Disable auto-release of parachute (i.e. release triggered by crash detectors). - - - Enable auto-release of parachute. - - - Release parachute and kill motors. - - - - - Encoding of payload unknown. - - - Registered for STorM32 gimbal controller. - - - Registered for STorM32 gimbal controller. - - - Registered for STorM32 gimbal controller. - - - Registered for STorM32 gimbal controller. - - - Registered for STorM32 gimbal controller. - - - Registered for STorM32 gimbal controller. - - - Registered for STorM32 gimbal controller. - - - Registered for STorM32 gimbal controller. - - - Registered for STorM32 gimbal controller. - - - Registered for STorM32 gimbal controller. - - - - - No type defined. - - - Manufacturer Serial Number (ANSI/CTA-2063 format). - - - CAA (Civil Aviation Authority) registered ID. Format: [ICAO Country Code].[CAA Assigned ID]. - - - UTM (Unmanned Traffic Management) assigned UUID (RFC4122). - - - A 20 byte ID for a specific flight/session. The exact ID type is indicated by the first byte of uas_id and these type values are managed by ICAO. - - - - - No UA (Unmanned Aircraft) type defined. - - - Aeroplane/Airplane. Fixed wing. - - - Helicopter or multirotor. - - - Gyroplane. - - - VTOL (Vertical Take-Off and Landing). Fixed wing aircraft that can take off vertically. - - - Ornithopter. - - - Glider. - - - Kite. - - - Free Balloon. - - - Captive Balloon. - - - Airship. E.g. a blimp. - - - Free Fall/Parachute (unpowered). - - - Rocket. - - - Tethered powered aircraft. - - - Ground Obstacle. - - - Other type of aircraft not listed earlier. - - - - - The status of the (UA) Unmanned Aircraft is undefined. - - - The UA is on the ground. - - - The UA is in the air. - - - The UA is having an emergency. - - - The remote ID system is failing or unreliable in some way. - - - - - The height field is relative to the take-off location. - - - The height field is relative to ground. - - - - - The horizontal accuracy is unknown. - - - The horizontal accuracy is smaller than 10 Nautical Miles. 18.52 km. - - - The horizontal accuracy is smaller than 4 Nautical Miles. 7.408 km. - - - The horizontal accuracy is smaller than 2 Nautical Miles. 3.704 km. - - - The horizontal accuracy is smaller than 1 Nautical Miles. 1.852 km. - - - The horizontal accuracy is smaller than 0.5 Nautical Miles. 926 m. - - - The horizontal accuracy is smaller than 0.3 Nautical Miles. 555.6 m. - - - The horizontal accuracy is smaller than 0.1 Nautical Miles. 185.2 m. - - - The horizontal accuracy is smaller than 0.05 Nautical Miles. 92.6 m. - - - The horizontal accuracy is smaller than 30 meter. - - - The horizontal accuracy is smaller than 10 meter. - - - The horizontal accuracy is smaller than 3 meter. - - - The horizontal accuracy is smaller than 1 meter. - - - - - The vertical accuracy is unknown. - - - The vertical accuracy is smaller than 150 meter. - - - The vertical accuracy is smaller than 45 meter. - - - The vertical accuracy is smaller than 25 meter. - - - The vertical accuracy is smaller than 10 meter. - - - The vertical accuracy is smaller than 3 meter. - - - The vertical accuracy is smaller than 1 meter. - - - - - The speed accuracy is unknown. - - - The speed accuracy is smaller than 10 meters per second. - - - The speed accuracy is smaller than 3 meters per second. - - - The speed accuracy is smaller than 1 meters per second. - - - The speed accuracy is smaller than 0.3 meters per second. - - - - - The timestamp accuracy is unknown. - - - The timestamp accuracy is smaller than or equal to 0.1 second. - - - The timestamp accuracy is smaller than or equal to 0.2 second. - - - The timestamp accuracy is smaller than or equal to 0.3 second. - - - The timestamp accuracy is smaller than or equal to 0.4 second. - - - The timestamp accuracy is smaller than or equal to 0.5 second. - - - The timestamp accuracy is smaller than or equal to 0.6 second. - - - The timestamp accuracy is smaller than or equal to 0.7 second. - - - The timestamp accuracy is smaller than or equal to 0.8 second. - - - The timestamp accuracy is smaller than or equal to 0.9 second. - - - The timestamp accuracy is smaller than or equal to 1.0 second. - - - The timestamp accuracy is smaller than or equal to 1.1 second. - - - The timestamp accuracy is smaller than or equal to 1.2 second. - - - The timestamp accuracy is smaller than or equal to 1.3 second. - - - The timestamp accuracy is smaller than or equal to 1.4 second. - - - The timestamp accuracy is smaller than or equal to 1.5 second. - - - - - No authentication type is specified. - - - Signature for the UAS (Unmanned Aircraft System) ID. - - - Signature for the Operator ID. - - - Signature for the entire message set. - - - Authentication is provided by Network Remote ID. - - - The exact authentication type is indicated by the first byte of authentication_data and these type values are managed by ICAO. - - - - - Optional free-form text description of the purpose of the flight. - - - Optional additional clarification when status == MAV_ODID_STATUS_EMERGENCY. - - - Optional additional clarification when status != MAV_ODID_STATUS_EMERGENCY. - - - - - The location/altitude of the operator is the same as the take-off location. - - - The location/altitude of the operator is dynamic. E.g. based on live GNSS data. - - - The location/altitude of the operator are fixed values. - - - - - The classification type for the UA is undeclared. - - - The classification type for the UA follows EU (European Union) specifications. - - - - - The category for the UA, according to the EU specification, is undeclared. - - - The category for the UA, according to the EU specification, is the Open category. - - - The category for the UA, according to the EU specification, is the Specific category. - - - The category for the UA, according to the EU specification, is the Certified category. - - - - - The class for the UA, according to the EU specification, is undeclared. - - - The class for the UA, according to the EU specification, is Class 0. - - - The class for the UA, according to the EU specification, is Class 1. - - - The class for the UA, according to the EU specification, is Class 2. - - - The class for the UA, according to the EU specification, is Class 3. - - - The class for the UA, according to the EU specification, is Class 4. - - - The class for the UA, according to the EU specification, is Class 5. - - - The class for the UA, according to the EU specification, is Class 6. - - - - - CAA (Civil Aviation Authority) registered operator ID. - - - - - Passing arming checks. - - - Generic arming failure, see error string for details. - - - - Tune formats (used for vehicle buzzer/tone generation). - - Format is QBasic 1.1 Play: https://www.qbasic.net/en/reference/qb11/Statement/PLAY-006.htm. - - - Format is Modern Music Markup Language (MML): https://en.wikipedia.org/wiki/Music_Macro_Language#Modern_MML. - - - - - Type of AIS vessel, enum duplicated from AIS standard, https://gpsd.gitlab.io/gpsd/AIVDM.html - - Not available (default). - - - - - - - - - - - - - - - - - - - - - - Wing In Ground effect. - - - - - - - - - - - - - - Towing: length exceeds 200m or breadth exceeds 25m. - - - Dredging or other underwater ops. - - - - - - - - - High Speed Craft. - - - - - - - - - - - - - Search And Rescue vessel. - - - - - Anti-pollution equipment. - - - - - - - Noncombatant ship according to RR Resolution No. 18. - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - Navigational status of AIS vessel, enum duplicated from AIS standard, https://gpsd.gitlab.io/gpsd/AIVDM.html - - Under way using engine. - - - - - - - - - - - - - - - - Search And Rescue Transponder. - - - Not available (default). - - - - These flags are used in the AIS_VESSEL.fields bitmask to indicate validity of data in the other message fields. When set, the data is valid. - - 1 = Position accuracy less than 10m, 0 = position accuracy greater than 10m. - - - - - 1 = Velocity over 52.5765m/s (102.2 knots) - - - - Only the sign of the returned turn rate value is valid, either greater than 5deg/30s or less than -5deg/30s - - - - Distance to bow is larger than 511m - - - Distance to stern is larger than 511m - - - Distance to port side is larger than 63m - - - Distance to starboard side is larger than 63m - - - - - - - List of possible units where failures can be injected. - - - - - - - - - - - - - - - - - - - List of possible failure type to inject. - - No failure injected, used to reset a previous failure. - - - Sets unit off, so completely non-responsive. - - - Unit is stuck e.g. keeps reporting the same value. - - - Unit is reporting complete garbage. - - - Unit is consistently wrong. - - - Unit is slow, so e.g. reporting at slower than expected rate. - - - Data of unit is delayed in time. - - - Unit is sometimes working, sometimes not. - - - - - Default autopilot landing behaviour. - - - Descend in fixed wing mode, transitioning to multicopter mode for vertical landing when close to the ground. - The fixed wing descent pattern is at the discretion of the vehicle (e.g. transition altitude, loiter direction, radius, and speed, etc.). - - - - Land in multicopter mode on reaching the landing coordinates (the whole landing is by "hover descent"). - - - - Winch status flags used in WINCH_STATUS - - Winch is healthy - - - Winch line is fully retracted - - - Winch motor is moving - - - Winch clutch is engaged allowing motor to move freely. - - - Winch is locked by locking mechanism. - - - Winch is gravity dropping payload. - - - Winch is arresting payload descent. - - - Winch is using torque measurements to sense the ground. - - - Winch is returning to the fully retracted position. - - - Winch is redelivering the payload. This is a failover state if the line tension goes above a threshold during RETRACTING. - - - Winch is abandoning the line and possibly payload. Winch unspools the entire calculated line length. This is a failover state from REDELIVER if the number of attempts exceeds a threshold. - - - Winch is engaging the locking mechanism. - - - Winch is spooling on line. - - - Winch is loading a payload. - - - - - - - - - - - - - - Reason for an event error response. - - The requested event is not available (anymore). - - - - Flags for CURRENT_EVENT_SEQUENCE. - - A sequence reset has happened (e.g. vehicle reboot). - - - - Flags in the HIL_SENSOR message indicate which fields have updated since the last message - - None of the fields in HIL_SENSOR have been updated - - - The value in the xacc field has been updated - - - The value in the yacc field has been updated - - - The value in the zacc field has been updated - - - The value in the xgyro field has been updated - - - The value in the ygyro field has been updated - - - The value in the zgyro field has been updated - - - The value in the xmag field has been updated - - - The value in the ymag field has been updated - - - The value in the zmag field has been updated - - - The value in the abs_pressure field has been updated - - - The value in the diff_pressure field has been updated - - - The value in the pressure_alt field has been updated - - - The value in the temperature field has been updated - - - Full reset of attitude/position/velocities/etc was performed in sim (Bit 31). - - - - Flags in the HIGHRES_IMU message indicate which fields have updated since the last message - - None of the fields in HIGHRES_IMU have been updated - - - The value in the xacc field has been updated - - - The value in the yacc field has been updated - - - The value in the zacc field has been updated since - - - The value in the xgyro field has been updated - - - The value in the ygyro field has been updated - - - The value in the zgyro field has been updated - - - The value in the xmag field has been updated - - - The value in the ymag field has been updated - - - The value in the zmag field has been updated - - - The value in the abs_pressure field has been updated - - - The value in the diff_pressure field has been updated - - - The value in the pressure_alt field has been updated - - - The value in the temperature field has been updated - - - All fields in HIGHRES_IMU have been updated. - - - - - - - - - MAV FTP error codes (https://mavlink.io/en/services/ftp.html) - - None: No error - - - Fail: Unknown failure - - - FailErrno: Command failed, Err number sent back in PayloadHeader.data[1]. - This is a file-system error number understood by the server operating system. - - - InvalidDataSize: Payload size is invalid - - - InvalidSession: Session is not currently open - - - NoSessionsAvailable: All available sessions are already in use - - - EOF: Offset past end of file for ListDirectory and ReadFile commands - - - UnknownCommand: Unknown command / opcode - - - FileExists: File/directory already exists - - - FileProtected: File/directory is write protected - - - FileNotFound: File/directory not found - - - - MAV FTP opcodes: https://mavlink.io/en/services/ftp.html - - None. Ignored, always ACKed - - - TerminateSession: Terminates open Read session - - - ResetSessions: Terminates all open read sessions - - - ListDirectory. List files and directories in path from offset - - - OpenFileRO: Opens file at path for reading, returns session - - - ReadFile: Reads size bytes from offset in session - - - CreateFile: Creates file at path for writing, returns session - - - WriteFile: Writes size bytes to offset in session - - - RemoveFile: Remove file at path - - - CreateDirectory: Creates directory at path - - - RemoveDirectory: Removes directory at path. The directory must be empty. - - - OpenFileWO: Opens file at path for writing, returns session - - - TruncateFile: Truncate file at path to offset length - - - Rename: Rename path1 to path2 - - - CalcFileCRC32: Calculate CRC32 for file at path - - - BurstReadFile: Burst download session file - - - ACK: ACK response - - - NAK: NAK response - - - - - States of the mission state machine. - Note that these states are independent of whether the mission is in a mode that can execute mission items or not (is suspended). - They may not all be relevant on all vehicles. - - - The mission status reporting is not supported. - - - No mission on the vehicle. - - - Mission has not started. This is the case after a mission has uploaded but not yet started executing. - - - Mission is active, and will execute mission items when in auto mode. - - - Mission is paused when in auto mode. - - - Mission has executed all mission items. - - - - - - The general system state. If the system is following the MAVLink standard, the system state is mainly defined by three orthogonal states/modes: The system mode, which is either LOCKED (motors shut down and locked), MANUAL (system under RC control), GUIDED (system with autonomous position control, position setpoint controlled manually) or AUTO (system guided by path/waypoint planner). The NAV_MODE defined the current flight state: LIFTOFF (often an open-loop maneuver), LANDING, WAYPOINTS or VECTOR. This represents the internal navigation state machine. The system status shows whether the system is currently active or not and if an emergency occurred. During the CRITICAL and EMERGENCY states the MAV is still considered to be active, but should start emergency procedures autonomously. After a failure occurred it should first move from active to critical to allow manual intervention and then move to emergency after a certain timeout. - Bitmap showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present. - Bitmap showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled. - Bitmap showing which onboard controllers and sensors have an error (or are operational). Value of 0: error. Value of 1: healthy. - Maximum usage in percent of the mainloop time. Values: [0-1000] - should always be below 1000 - Battery voltage, UINT16_MAX: Voltage not sent by autopilot - Battery current, -1: Current not sent by autopilot - Battery energy remaining, -1: Battery remaining energy not sent by autopilot - Communication drop rate, (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) - Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) - Autopilot-specific errors - Autopilot-specific errors - Autopilot-specific errors - Autopilot-specific errors - - Bitmap showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present. - Bitmap showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled. - Bitmap showing which onboard controllers and sensors have an error (or are operational). Value of 0: error. Value of 1: healthy. - - - The system time is the time of the master clock, typically the computer clock of the main onboard computer. - Timestamp (UNIX epoch time). - Timestamp (time since system boot). - - - to be removed / merged with SYSTEM_TIME - A ping message either requesting or responding to a ping. This allows to measure the system latencies, including serial port, radio modem and UDP connections. The ping microservice is documented at https://mavlink.io/en/services/ping.html - Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - PING sequence - 0: request ping from all receiving systems. If greater than 0: message is a ping response and number is the system id of the requesting system - 0: request ping from all receiving components. If greater than 0: message is a ping response and number is the component id of the requesting component. - - - Request to control this MAV - System the GCS requests control for - 0: request control of this MAV, 1: Release control of this MAV - 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch. - Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-" - - - Accept / deny control of this MAV - ID of the GCS this message - 0: request control of this MAV, 1: Release control of this MAV - 0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control - - - Emit an encrypted signature / key identifying this system. PLEASE NOTE: This protocol has been kept simple, so transmitting the key requires an encrypted channel for true safety. - key - - - - - Status generated in each node in the communication chain and injected into MAVLink stream. - Timestamp (time since system boot). - Remaining free transmit buffer space - Remaining free receive buffer space - Transmit rate - Receive rate - Number of bytes that could not be parsed correctly. - Transmit buffer overflows. This number wraps around as it reaches UINT16_MAX - Receive buffer overflows. This number wraps around as it reaches UINT16_MAX - Messages sent - Messages received (estimated from counting seq) - Messages lost (estimated from counting seq) - - - Use COMMAND_LONG with MAV_CMD_DO_SET_MODE instead - Set the system mode, as defined by enum MAV_MODE. There is no target component id as the mode is by definition for the overall aircraft, not only for one component. - The system setting the mode - The new base mode. - The new autopilot-specific mode. This field can be ignored by an autopilot. - - - - - Request to read the onboard parameter with the param_id string id. Onboard parameters are stored as key[const char*] -> value[float]. This allows to send a parameter to any other component (such as the GCS) without the need of previous knowledge of possible parameter names. Thus the same GCS can store different parameters for different autopilots. See also https://mavlink.io/en/services/parameter.html for a full documentation of QGroundControl and IMU code. - System ID - Component ID - Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string - Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored) - - - Request all parameters of this component. After this request, all parameters are emitted. The parameter microservice is documented at https://mavlink.io/en/services/parameter.html - System ID - Component ID - - - Emit the value of a onboard parameter. The inclusion of param_count and param_index in the message allows the recipient to keep track of received parameters and allows him to re-request missing parameters after a loss or timeout. The parameter microservice is documented at https://mavlink.io/en/services/parameter.html - Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string - Onboard parameter value - Onboard parameter type. - Total number of onboard parameters - Index of this onboard parameter - - - Set a parameter value (write new value to permanent storage). - The receiving component should acknowledge the new parameter value by broadcasting a PARAM_VALUE message (broadcasting ensures that multiple GCS all have an up-to-date list of all parameters). If the sending GCS did not receive a PARAM_VALUE within its timeout time, it should re-send the PARAM_SET message. The parameter microservice is documented at https://mavlink.io/en/services/parameter.html. - PARAM_SET may also be called within the context of a transaction (started with MAV_CMD_PARAM_TRANSACTION). Within a transaction the receiving component should respond with PARAM_ACK_TRANSACTION to the setter component (instead of broadcasting PARAM_VALUE), and PARAM_SET should be re-sent if this is ACK not received. - System ID - Component ID - Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string - Onboard parameter value - Onboard parameter type. - - - The global position, as returned by the Global Positioning System (GPS). This is - NOT the global position estimate of the system, but rather a RAW sensor value. See message GLOBAL_POSITION_INT for the global position estimate. - Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - GPS fix type. - Latitude (WGS84, EGM96 ellipsoid) - Longitude (WGS84, EGM96 ellipsoid) - Altitude (MSL). Positive for up. Note that virtually all GPS modules provide the MSL altitude in addition to the WGS84 altitude. - GPS HDOP horizontal dilution of position (unitless * 100). If unknown, set to: UINT16_MAX - GPS VDOP vertical dilution of position (unitless * 100). If unknown, set to: UINT16_MAX - GPS ground speed. If unknown, set to: UINT16_MAX - Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX - Number of satellites visible. If unknown, set to UINT8_MAX - - Altitude (above WGS84, EGM96 ellipsoid). Positive for up. - Position uncertainty. - Altitude uncertainty. - Speed uncertainty. - Heading / track uncertainty - Yaw in earth frame from north. Use 0 if this GPS does not provide yaw. Use UINT16_MAX if this GPS is configured to provide yaw and is currently unable to provide it. Use 36000 for north. - - - The positioning status, as reported by GPS. This message is intended to display status information about each satellite visible to the receiver. See message GLOBAL_POSITION_INT for the global position estimate. This message can contain information for up to 20 satellites. - Number of satellites visible - Global satellite ID - 0: Satellite not used, 1: used for localization - Elevation (0: right on top of receiver, 90: on the horizon) of satellite - Direction of satellite, 0: 0 deg, 255: 360 deg. - Signal to noise ratio of satellite - - - The RAW IMU readings for the usual 9DOF sensor setup. This message should contain the scaled values to the described units - Timestamp (time since system boot). - X acceleration - Y acceleration - Z acceleration - Angular speed around X axis - Angular speed around Y axis - Angular speed around Z axis - X Magnetic field - Y Magnetic field - Z Magnetic field - - Temperature, 0: IMU does not provide temperature values. If the IMU is at 0C it must send 1 (0.01C). - - - The RAW IMU readings for a 9DOF sensor, which is identified by the id (default IMU1). This message should always contain the true raw values without any scaling to allow data capture and system debugging. - Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - X acceleration (raw) - Y acceleration (raw) - Z acceleration (raw) - Angular speed around X axis (raw) - Angular speed around Y axis (raw) - Angular speed around Z axis (raw) - X Magnetic field (raw) - Y Magnetic field (raw) - Z Magnetic field (raw) - - Id. Ids are numbered from 0 and map to IMUs numbered from 1 (e.g. IMU1 will have a message with id=0) - Temperature, 0: IMU does not provide temperature values. If the IMU is at 0C it must send 1 (0.01C). - - - The RAW pressure readings for the typical setup of one absolute pressure and one differential pressure sensor. The sensor values should be the raw, UNSCALED ADC values. - Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - Absolute pressure (raw) - Differential pressure 1 (raw, 0 if nonexistent) - Differential pressure 2 (raw, 0 if nonexistent) - Raw Temperature measurement (raw) - - - The pressure readings for the typical setup of one absolute and differential pressure sensor. The units are as specified in each field. - Timestamp (time since system boot). - Absolute pressure - Differential pressure 1 - Absolute pressure temperature - - Differential pressure temperature (0, if not available). Report values of 0 (or 1) as 1 cdegC. - - - The attitude in the aeronautical frame (right-handed, Z-down, Y-right, X-front, ZYX, intrinsic). - Timestamp (time since system boot). - Roll angle (-pi..+pi) - Pitch angle (-pi..+pi) - Yaw angle (-pi..+pi) - Roll angular speed - Pitch angular speed - Yaw angular speed - - - The attitude in the aeronautical frame (right-handed, Z-down, X-front, Y-right), expressed as quaternion. Quaternion order is w, x, y, z and a zero rotation would be expressed as (1 0 0 0). - Timestamp (time since system boot). - Quaternion component 1, w (1 in null-rotation) - Quaternion component 2, x (0 in null-rotation) - Quaternion component 3, y (0 in null-rotation) - Quaternion component 4, z (0 in null-rotation) - Roll angular speed - Pitch angular speed - Yaw angular speed - - Rotation offset by which the attitude quaternion and angular speed vector should be rotated for user display (quaternion with [w, x, y, z] order, zero-rotation is [1, 0, 0, 0], send [0, 0, 0, 0] if field not supported). This field is intended for systems in which the reference attitude may change during flight. For example, tailsitters VTOLs rotate their reference attitude by 90 degrees between hover mode and fixed wing mode, thus repr_offset_q is equal to [1, 0, 0, 0] in hover mode and equal to [0.7071, 0, 0.7071, 0] in fixed wing mode. - - - The filtered local position (e.g. fused computer vision and accelerometers). Coordinate frame is right-handed, Z-axis down (aeronautical frame, NED / north-east-down convention) - Timestamp (time since system boot). - X Position - Y Position - Z Position - X Speed - Y Speed - Z Speed - - - The filtered global position (e.g. fused GPS and accelerometers). The position is in GPS-frame (right-handed, Z-up). It - is designed as scaled integer message since the resolution of float is not sufficient. - Timestamp (time since system boot). - Latitude, expressed - Longitude, expressed - Altitude (MSL). Note that virtually all GPS modules provide both WGS84 and MSL. - Altitude above ground - Ground X Speed (Latitude, positive north) - Ground Y Speed (Longitude, positive east) - Ground Z Speed (Altitude, positive down) - Vehicle heading (yaw angle), 0.0..359.99 degrees. If unknown, set to: UINT16_MAX - - - The scaled values of the RC channels received: (-100%) -10000, (0%) 0, (100%) 10000. Channels that are inactive should be set to UINT16_MAX. - Timestamp (time since system boot). - Servo output port (set of 8 outputs = 1 port). Flight stacks running on Pixhawk should use: 0 = MAIN, 1 = AUX. - RC channel 1 value scaled. - RC channel 2 value scaled. - RC channel 3 value scaled. - RC channel 4 value scaled. - RC channel 5 value scaled. - RC channel 6 value scaled. - RC channel 7 value scaled. - RC channel 8 value scaled. - Receive signal strength indicator in device-dependent units/scale. Values: [0-254], UINT8_MAX: invalid/unknown. - - - The RAW values of the RC channels received. The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. A value of UINT16_MAX implies the channel is unused. Individual receivers/transmitters might violate this specification. - Timestamp (time since system boot). - Servo output port (set of 8 outputs = 1 port). Flight stacks running on Pixhawk should use: 0 = MAIN, 1 = AUX. - RC channel 1 value. - RC channel 2 value. - RC channel 3 value. - RC channel 4 value. - RC channel 5 value. - RC channel 6 value. - RC channel 7 value. - RC channel 8 value. - Receive signal strength indicator in device-dependent units/scale. Values: [0-254], UINT8_MAX: invalid/unknown. - - - Superseded by ACTUATOR_OUTPUT_STATUS. The RAW values of the servo outputs (for RC input from the remote, use the RC_CHANNELS messages). The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. - Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - Servo output port (set of 8 outputs = 1 port). Flight stacks running on Pixhawk should use: 0 = MAIN, 1 = AUX. - Servo output 1 value - Servo output 2 value - Servo output 3 value - Servo output 4 value - Servo output 5 value - Servo output 6 value - Servo output 7 value - Servo output 8 value - - Servo output 9 value - Servo output 10 value - Servo output 11 value - Servo output 12 value - Servo output 13 value - Servo output 14 value - Servo output 15 value - Servo output 16 value - - - Request a partial list of mission items from the system/component. https://mavlink.io/en/services/mission.html. If start and end index are the same, just send one waypoint. - System ID - Component ID - Start index - End index, -1 by default (-1: send list to end). Else a valid index of the list - - Mission type. - - - This message is sent to the MAV to write a partial list. If start index == end index, only one item will be transmitted / updated. If the start index is NOT 0 and above the current list size, this request should be REJECTED! - System ID - Component ID - Start index. Must be smaller / equal to the largest index of the current onboard list. - End index, equal or greater than start index. - - Mission type. - - - - Message encoding a mission item. This message is emitted to announce - the presence of a mission item and to set a mission item on the system. The mission item can be either in x, y, z meters (type: LOCAL) or x:lat, y:lon, z:altitude. Local frame is Z-down, right handed (NED), global frame is Z-up, right handed (ENU). NaN may be used to indicate an optional/default value (e.g. to use the system's current latitude or yaw rather than a specific value). See also https://mavlink.io/en/services/mission.html. - System ID - Component ID - Sequence - The coordinate system of the waypoint. - The scheduled action for the waypoint. - false:0, true:1 - Autocontinue to next waypoint. 0: false, 1: true. Set false to pause mission after the item completes. - PARAM1, see MAV_CMD enum - PARAM2, see MAV_CMD enum - PARAM3, see MAV_CMD enum - PARAM4, see MAV_CMD enum - PARAM5 / local: X coordinate, global: latitude - PARAM6 / local: Y coordinate, global: longitude - PARAM7 / local: Z coordinate, global: altitude (relative or absolute, depending on frame). - - Mission type. - - - A system that gets this request should respond with MISSION_ITEM_INT (as though MISSION_REQUEST_INT was received). - Request the information of the mission item with the sequence number seq. The response of the system to this message should be a MISSION_ITEM message. https://mavlink.io/en/services/mission.html - System ID - Component ID - Sequence - - Mission type. - - - - - Set the mission item with sequence number seq as the current item and emit MISSION_CURRENT (whether or not the mission number changed). - If a mission is currently being executed, the system will continue to this new mission item on the shortest path, skipping any intermediate mission items. - Note that mission jump repeat counters are not reset (see MAV_CMD_DO_JUMP param2). - - This message may trigger a mission state-machine change on some systems: for example from MISSION_STATE_NOT_STARTED or MISSION_STATE_PAUSED to MISSION_STATE_ACTIVE. - If the system is in mission mode, on those systems this command might therefore start, restart or resume the mission. - If the system is not in mission mode this message must not trigger a switch to mission mode. - - System ID - Component ID - Sequence - - - - Message that announces the sequence number of the current target mission item (that the system will fly towards/execute when the mission is running). - This message should be streamed all the time (nominally at 1Hz). - This message should be emitted following a call to MAV_CMD_DO_SET_MISSION_CURRENT or SET_MISSION_CURRENT. - - Sequence - - Total number of mission items on vehicle (on last item, sequence == total). If the autopilot stores its home location as part of the mission this will be excluded from the total. 0: Not supported, UINT16_MAX if no mission is present on the vehicle. - Mission state machine state. MISSION_STATE_UNKNOWN if state reporting not supported. - Vehicle is in a mode that can execute mission items or suspended. 0: Unknown, 1: In mission mode, 2: Suspended (not in mission mode). - - - Request the overall list of mission items from the system/component. - System ID - Component ID - - Mission type. - - - This message is emitted as response to MISSION_REQUEST_LIST by the MAV and to initiate a write transaction. The GCS can then request the individual mission item based on the knowledge of the total number of waypoints. - System ID - Component ID - Number of mission items in the sequence - - Mission type. - - - Delete all mission items at once. - System ID - Component ID - - Mission type. - - - A certain mission item has been reached. The system will either hold this position (or circle on the orbit) or (if the autocontinue on the WP was set) continue to the next waypoint. - Sequence - - - Acknowledgment message during waypoint handling. The type field states if this message is a positive ack (type=0) or if an error happened (type=non-zero). - System ID - Component ID - Mission result. - - Mission type. - - - Sets the GPS coordinates of the vehicle local origin (0,0,0) position. Vehicle should emit GPS_GLOBAL_ORIGIN irrespective of whether the origin is changed. This enables transform between the local coordinate frame and the global (GPS) coordinate frame, which may be necessary when (for example) indoor and outdoor settings are connected and the MAV should move from in- to outdoor. - System ID - Latitude (WGS84) - Longitude (WGS84) - Altitude (MSL). Positive for up. - - Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - - - Publishes the GPS coordinates of the vehicle local origin (0,0,0) position. Emitted whenever a new GPS-Local position mapping is requested or set - e.g. following SET_GPS_GLOBAL_ORIGIN message. - Latitude (WGS84) - Longitude (WGS84) - Altitude (MSL). Positive for up. - - Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - - - Bind a RC channel to a parameter. The parameter should change according to the RC channel value. - System ID - Component ID - Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string - Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored), send -2 to disable any existing map for this rc_channel_index. - Index of parameter RC channel. Not equal to the RC channel id. Typically corresponds to a potentiometer-knob on the RC. - Initial parameter value - Scale, maps the RC range [-1, 1] to a parameter value - Minimum param value. The protocol does not define if this overwrites an onboard minimum value. (Depends on implementation) - Maximum param value. The protocol does not define if this overwrites an onboard maximum value. (Depends on implementation) - - - Request the information of the mission item with the sequence number seq. The response of the system to this message should be a MISSION_ITEM_INT message. https://mavlink.io/en/services/mission.html - System ID - Component ID - Sequence - - Mission type. - - - - Set a safety zone (volume), which is defined by two corners of a cube. This message can be used to tell the MAV which setpoints/waypoints to accept and which to reject. Safety areas are often enforced by national or competition regulations. - System ID - Component ID - Coordinate frame. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. - x position 1 / Latitude 1 - y position 1 / Longitude 1 - z position 1 / Altitude 1 - x position 2 / Latitude 2 - y position 2 / Longitude 2 - z position 2 / Altitude 2 - - - Read out the safety zone the MAV currently assumes. - Coordinate frame. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. - x position 1 / Latitude 1 - y position 1 / Longitude 1 - z position 1 / Altitude 1 - x position 2 / Latitude 2 - y position 2 / Longitude 2 - z position 2 / Altitude 2 - - - The attitude in the aeronautical frame (right-handed, Z-down, X-front, Y-right), expressed as quaternion. Quaternion order is w, x, y, z and a zero rotation would be expressed as (1 0 0 0). - Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation) - Roll angular speed - Pitch angular speed - Yaw angular speed - Row-major representation of a 3x3 attitude covariance matrix (states: roll, pitch, yaw; first three entries are the first ROW, next three entries are the second row, etc.). If unknown, assign NaN value to first element in the array. - - - The state of the navigation and position controller. - Current desired roll - Current desired pitch - Current desired heading - Bearing to current waypoint/target - Distance to active waypoint - Current altitude error - Current airspeed error - Current crosstrack error on x-y plane - - - The filtered global position (e.g. fused GPS and accelerometers). The position is in GPS-frame (right-handed, Z-up). It is designed as scaled integer message since the resolution of float is not sufficient. NOTE: This message is intended for onboard networks / companion computers and higher-bandwidth links and optimized for accuracy and completeness. Please use the GLOBAL_POSITION_INT message for a minimal subset. - Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - Class id of the estimator this estimate originated from. - Latitude - Longitude - Altitude in meters above MSL - Altitude above ground - Ground X Speed (Latitude) - Ground Y Speed (Longitude) - Ground Z Speed (Altitude) - Row-major representation of a 6x6 position and velocity 6x6 cross-covariance matrix (states: lat, lon, alt, vx, vy, vz; first six entries are the first ROW, next six entries are the second row, etc.). If unknown, assign NaN value to first element in the array. - - - The filtered local position (e.g. fused computer vision and accelerometers). Coordinate frame is right-handed, Z-axis down (aeronautical frame, NED / north-east-down convention) - Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - Class id of the estimator this estimate originated from. - X Position - Y Position - Z Position - X Speed - Y Speed - Z Speed - X Acceleration - Y Acceleration - Z Acceleration - Row-major representation of position, velocity and acceleration 9x9 cross-covariance matrix upper right triangle (states: x, y, z, vx, vy, vz, ax, ay, az; first nine entries are the first ROW, next eight entries are the second row, etc.). If unknown, assign NaN value to first element in the array. - - - The PPM values of the RC channels received. The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. A value of UINT16_MAX implies the channel is unused. Individual receivers/transmitters might violate this specification. - Timestamp (time since system boot). - Total number of RC channels being received. This can be larger than 18, indicating that more channels are available but not given in this message. This value should be 0 when no RC channels are available. - RC channel 1 value. - RC channel 2 value. - RC channel 3 value. - RC channel 4 value. - RC channel 5 value. - RC channel 6 value. - RC channel 7 value. - RC channel 8 value. - RC channel 9 value. - RC channel 10 value. - RC channel 11 value. - RC channel 12 value. - RC channel 13 value. - RC channel 14 value. - RC channel 15 value. - RC channel 16 value. - RC channel 17 value. - RC channel 18 value. - Receive signal strength indicator in device-dependent units/scale. Values: [0-254], UINT8_MAX: invalid/unknown. - - - - Request a data stream. - The target requested to send the message stream. - The target requested to send the message stream. - The ID of the requested data stream - The requested message rate - 1 to start sending, 0 to stop sending. - - - - Data stream status information. - The ID of the requested data stream - The message rate - 1 stream is enabled, 0 stream is stopped. - - - This message provides an API for manually controlling the vehicle using standard joystick axes nomenclature, along with a joystick-like input device. Unused axes can be disabled and buttons states are transmitted as individual on/off bits of a bitmask - The system to be controlled. - X-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to forward(1000)-backward(-1000) movement on a joystick and the pitch of a vehicle. - Y-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to left(-1000)-right(1000) movement on a joystick and the roll of a vehicle. - Z-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a separate slider movement with maximum being 1000 and minimum being -1000 on a joystick and the thrust of a vehicle. Positive values are positive thrust, negative values are negative thrust. - R-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a twisting of the joystick, with counter-clockwise being 1000 and clockwise being -1000, and the yaw of a vehicle. - A bitfield corresponding to the joystick buttons' 0-15 current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 1. - - A bitfield corresponding to the joystick buttons' 16-31 current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 16. - Set bits to 1 to indicate which of the following extension fields contain valid data: bit 0: pitch, bit 1: roll. - Pitch-only-axis, normalized to the range [-1000,1000]. Generally corresponds to pitch on vehicles with additional degrees of freedom. Valid if bit 0 of enabled_extensions field is set. Set to 0 if invalid. - Roll-only-axis, normalized to the range [-1000,1000]. Generally corresponds to roll on vehicles with additional degrees of freedom. Valid if bit 1 of enabled_extensions field is set. Set to 0 if invalid. - - - The RAW values of the RC channels sent to the MAV to override info received from the RC radio. The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. Individual receivers/transmitters might violate this specification. Note carefully the semantic differences between the first 8 channels and the subsequent channels - System ID - Component ID - RC channel 1 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio. - RC channel 2 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio. - RC channel 3 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio. - RC channel 4 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio. - RC channel 5 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio. - RC channel 6 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio. - RC channel 7 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio. - RC channel 8 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio. - - RC channel 9 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio. - RC channel 10 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio. - RC channel 11 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio. - RC channel 12 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio. - RC channel 13 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio. - RC channel 14 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio. - RC channel 15 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio. - RC channel 16 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio. - RC channel 17 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio. - RC channel 18 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio. - - - Message encoding a mission item. This message is emitted to announce - the presence of a mission item and to set a mission item on the system. The mission item can be either in x, y, z meters (type: LOCAL) or x:lat, y:lon, z:altitude. Local frame is Z-down, right handed (NED), global frame is Z-up, right handed (ENU). NaN or INT32_MAX may be used in float/integer params (respectively) to indicate optional/default values (e.g. to use the component's current latitude, yaw rather than a specific value). See also https://mavlink.io/en/services/mission.html. - System ID - Component ID - Waypoint ID (sequence number). Starts at zero. Increases monotonically for each waypoint, no gaps in the sequence (0,1,2,3,4). - The coordinate system of the waypoint. - The scheduled action for the waypoint. - false:0, true:1 - Autocontinue to next waypoint. 0: false, 1: true. Set false to pause mission after the item completes. - PARAM1, see MAV_CMD enum - PARAM2, see MAV_CMD enum - PARAM3, see MAV_CMD enum - PARAM4, see MAV_CMD enum - PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7 - PARAM6 / y position: local: x position in meters * 1e4, global: longitude in degrees *10^7 - PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame. - - Mission type. - - - Metrics typically displayed on a HUD for fixed wing aircraft. - Vehicle speed in form appropriate for vehicle type. For standard aircraft this is typically calibrated airspeed (CAS) or indicated airspeed (IAS) - either of which can be used by a pilot to estimate stall speed. - Current ground speed. - Current heading in compass units (0-360, 0=north). - Current throttle setting (0 to 100). - Current altitude (MSL). - Current climb rate. - - - Send a command with up to seven parameters to the MAV, where params 5 and 6 are integers and the other values are floats. This is preferred over COMMAND_LONG as it allows the MAV_FRAME to be specified for interpreting positional information, such as altitude. COMMAND_INT is also preferred when sending latitude and longitude data in params 5 and 6, as it allows for greater precision. Param 5 and 6 encode positional data as scaled integers, where the scaling depends on the actual command value. NaN or INT32_MAX may be used in float/integer params (respectively) to indicate optional/default values (e.g. to use the component's current latitude, yaw rather than a specific value). The command microservice is documented at https://mavlink.io/en/services/command.html - System ID - Component ID - The coordinate system of the COMMAND. - The scheduled action for the mission item. - Not used. - Not used (set 0). - PARAM1, see MAV_CMD enum - PARAM2, see MAV_CMD enum - PARAM3, see MAV_CMD enum - PARAM4, see MAV_CMD enum - PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7 - PARAM6 / local: y position in meters * 1e4, global: longitude in degrees * 10^7 - PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame). - - - Send a command with up to seven parameters to the MAV. COMMAND_INT is generally preferred when sending MAV_CMD commands that include positional information; it offers higher precision and allows the MAV_FRAME to be specified (which may otherwise be ambiguous, particularly for altitude). The command microservice is documented at https://mavlink.io/en/services/command.html - System which should execute the command - Component which should execute the command, 0 for all components - Command ID (of command to send). - 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) - Parameter 1 (for the specific command). - Parameter 2 (for the specific command). - Parameter 3 (for the specific command). - Parameter 4 (for the specific command). - Parameter 5 (for the specific command). - Parameter 6 (for the specific command). - Parameter 7 (for the specific command). - - - Report status of a command. Includes feedback whether the command was executed. The command microservice is documented at https://mavlink.io/en/services/command.html - Command ID (of acknowledged command). - Result of command. - - The progress percentage when result is MAV_RESULT_IN_PROGRESS. Values: [0-100], or UINT8_MAX if the progress is unknown. - Additional result information. Can be set with a command-specific enum containing command-specific error reasons for why the command might be denied. If used, the associated enum must be documented in the corresponding MAV_CMD (this enum should have a 0 value to indicate "unused" or "unknown"). - System ID of the target recipient. This is the ID of the system that sent the command for which this COMMAND_ACK is an acknowledgement. - Component ID of the target recipient. This is the ID of the system that sent the command for which this COMMAND_ACK is an acknowledgement. - - - - - Cancel a long running command. The target system should respond with a COMMAND_ACK to the original command with result=MAV_RESULT_CANCELLED if the long running process was cancelled. If it has already completed, the cancel action can be ignored. The cancel action can be retried until some sort of acknowledgement to the original command has been received. The command microservice is documented at https://mavlink.io/en/services/command.html - System executing long running command. Should not be broadcast (0). - Component executing long running command. - Command ID (of command to cancel). - - - Setpoint in roll, pitch, yaw and thrust from the operator - Timestamp (time since system boot). - Desired roll rate - Desired pitch rate - Desired yaw rate - Collective thrust, normalized to 0 .. 1 - Flight mode switch position, 0.. 255 - Override mode switch position, 0.. 255 - - - Sets a desired vehicle attitude. Used by an external controller to command the vehicle (manual controller or other system). - Timestamp (time since system boot). - System ID - Component ID - Bitmap to indicate which dimensions should be ignored by the vehicle. - Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) - Body roll rate - Body pitch rate - Body yaw rate - Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust) - - 3D thrust setpoint in the body NED frame, normalized to -1 .. 1 - - - Reports the current commanded attitude of the vehicle as specified by the autopilot. This should match the commands sent in a SET_ATTITUDE_TARGET message if the vehicle is being controlled this way. - Timestamp (time since system boot). - Bitmap to indicate which dimensions should be ignored by the vehicle. - Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) - Body roll rate - Body pitch rate - Body yaw rate - Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust) - - - Sets a desired vehicle position in a local north-east-down coordinate frame. Used by an external controller to command the vehicle (manual controller or other system). - Timestamp (time since system boot). - System ID - Component ID - Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9 - Bitmap to indicate which dimensions should be ignored by the vehicle. - X Position in NED frame - Y Position in NED frame - Z Position in NED frame (note, altitude is negative in NED) - X velocity in NED frame - Y velocity in NED frame - Z velocity in NED frame - X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - yaw setpoint - yaw rate setpoint - - - Reports the current commanded vehicle position, velocity, and acceleration as specified by the autopilot. This should match the commands sent in SET_POSITION_TARGET_LOCAL_NED if the vehicle is being controlled this way. - Timestamp (time since system boot). - Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9 - Bitmap to indicate which dimensions should be ignored by the vehicle. - X Position in NED frame - Y Position in NED frame - Z Position in NED frame (note, altitude is negative in NED) - X velocity in NED frame - Y velocity in NED frame - Z velocity in NED frame - X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - yaw setpoint - yaw rate setpoint - - - Sets a desired vehicle position, velocity, and/or acceleration in a global coordinate system (WGS84). Used by an external controller to command the vehicle (manual controller or other system). - Timestamp (time since system boot). The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency. - System ID - Component ID - Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11 - Bitmap to indicate which dimensions should be ignored by the vehicle. - X Position in WGS84 frame - Y Position in WGS84 frame - Altitude (MSL, Relative to home, or AGL - depending on frame) - X velocity in NED frame - Y velocity in NED frame - Z velocity in NED frame - X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - yaw setpoint - yaw rate setpoint - - - Reports the current commanded vehicle position, velocity, and acceleration as specified by the autopilot. This should match the commands sent in SET_POSITION_TARGET_GLOBAL_INT if the vehicle is being controlled this way. - Timestamp (time since system boot). The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency. - Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11 - Bitmap to indicate which dimensions should be ignored by the vehicle. - X Position in WGS84 frame - Y Position in WGS84 frame - Altitude (MSL, AGL or relative to home altitude, depending on frame) - X velocity in NED frame - Y velocity in NED frame - Z velocity in NED frame - X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N - yaw setpoint - yaw rate setpoint - - - The offset in X, Y, Z and yaw between the LOCAL_POSITION_NED messages of MAV X and the global coordinate frame in NED coordinates. Coordinate frame is right-handed, Z-axis down (aeronautical frame, NED / north-east-down convention) - Timestamp (time since system boot). - X Position - Y Position - Z Position - Roll - Pitch - Yaw - - - Suffers from missing airspeed fields and singularities due to Euler angles - Sent from simulation to autopilot. This packet is useful for high throughput applications such as hardware in the loop simulations. - Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - Roll angle - Pitch angle - Yaw angle - Body frame roll / phi angular speed - Body frame pitch / theta angular speed - Body frame yaw / psi angular speed - Latitude - Longitude - Altitude - Ground X Speed (Latitude) - Ground Y Speed (Longitude) - Ground Z Speed (Altitude) - X acceleration - Y acceleration - Z acceleration - - - Sent from autopilot to simulation. Hardware in the loop control outputs - Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - Control output -1 .. 1 - Control output -1 .. 1 - Control output -1 .. 1 - Throttle 0 .. 1 - Aux 1, -1 .. 1 - Aux 2, -1 .. 1 - Aux 3, -1 .. 1 - Aux 4, -1 .. 1 - System mode. - Navigation mode (MAV_NAV_MODE) - - - Sent from simulation to autopilot. The RAW values of the RC channels received. The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. Individual receivers/transmitters might violate this specification. - Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - RC channel 1 value - RC channel 2 value - RC channel 3 value - RC channel 4 value - RC channel 5 value - RC channel 6 value - RC channel 7 value - RC channel 8 value - RC channel 9 value - RC channel 10 value - RC channel 11 value - RC channel 12 value - Receive signal strength indicator in device-dependent units/scale. Values: [0-254], UINT8_MAX: invalid/unknown. - - - Sent from autopilot to simulation. Hardware in the loop control outputs (replacement for HIL_CONTROLS) - Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - Control outputs -1 .. 1. Channel assignment depends on the simulated hardware. - System mode. Includes arming state. - Flags as bitfield, 1: indicate simulation using lockstep. - - - Optical flow from a flow sensor (e.g. optical mouse sensor) - Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - Sensor ID - Flow in x-sensor direction - Flow in y-sensor direction - Flow in x-sensor direction, angular-speed compensated - Flow in y-sensor direction, angular-speed compensated - Optical flow quality / confidence. 0: bad, 255: maximum quality - Ground distance. Positive value: distance known. Negative value: Unknown distance - - Flow rate about X axis - Flow rate about Y axis - - - Global position/attitude estimate from a vision source. - Timestamp (UNIX time or since system boot) - Global X position - Global Y position - Global Z position - Roll angle - Pitch angle - Yaw angle - - Row-major representation of pose 6x6 cross-covariance matrix upper right triangle (states: x_global, y_global, z_global, roll, pitch, yaw; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array. - Estimate reset counter. This should be incremented when the estimate resets in any of the dimensions (position, velocity, attitude, angular speed). This is designed to be used when e.g an external SLAM system detects a loop-closure and the estimate jumps. - - - Local position/attitude estimate from a vision source. - Timestamp (UNIX time or time since system boot) - Local X position - Local Y position - Local Z position - Roll angle - Pitch angle - Yaw angle - - Row-major representation of pose 6x6 cross-covariance matrix upper right triangle (states: x, y, z, roll, pitch, yaw; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array. - Estimate reset counter. This should be incremented when the estimate resets in any of the dimensions (position, velocity, attitude, angular speed). This is designed to be used when e.g an external SLAM system detects a loop-closure and the estimate jumps. - - - Speed estimate from a vision source. - Timestamp (UNIX time or time since system boot) - Global X speed - Global Y speed - Global Z speed - - Row-major representation of 3x3 linear velocity covariance matrix (states: vx, vy, vz; 1st three entries - 1st row, etc.). If unknown, assign NaN value to first element in the array. - Estimate reset counter. This should be incremented when the estimate resets in any of the dimensions (position, velocity, attitude, angular speed). This is designed to be used when e.g an external SLAM system detects a loop-closure and the estimate jumps. - - - Global position estimate from a Vicon motion system source. - Timestamp (UNIX time or time since system boot) - Global X position - Global Y position - Global Z position - Roll angle - Pitch angle - Yaw angle - - Row-major representation of 6x6 pose cross-covariance matrix upper right triangle (states: x, y, z, roll, pitch, yaw; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array. - - - The IMU readings in SI units in NED body frame - Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - X acceleration - Y acceleration - Z acceleration - Angular speed around X axis - Angular speed around Y axis - Angular speed around Z axis - X Magnetic field - Y Magnetic field - Z Magnetic field - Absolute pressure - Differential pressure - Altitude calculated from pressure - Temperature - Bitmap for fields that have updated since last message - - Id. Ids are numbered from 0 and map to IMUs numbered from 1 (e.g. IMU1 will have a message with id=0) - - - Optical flow from an angular rate flow sensor (e.g. PX4FLOW or mouse sensor) - Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - Sensor ID - Integration time. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the. - Flow around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.) - Flow around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.) - RH rotation around X axis - RH rotation around Y axis - RH rotation around Z axis - Temperature - Optical flow quality / confidence. 0: no valid flow, 255: maximum quality - Time since the distance was sampled. - Distance to the center of the flow field. Positive value (including zero): distance known. Negative value: Unknown distance. - - - The IMU readings in SI units in NED body frame - Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - X acceleration - Y acceleration - Z acceleration - Angular speed around X axis in body frame - Angular speed around Y axis in body frame - Angular speed around Z axis in body frame - X Magnetic field - Y Magnetic field - Z Magnetic field - Absolute pressure - Differential pressure (airspeed) - Altitude calculated from pressure - Temperature - Bitmap for fields that have updated since last message - - Sensor ID (zero indexed). Used for multiple sensor inputs - - - Status of simulation environment, if used - True attitude quaternion component 1, w (1 in null-rotation) - True attitude quaternion component 2, x (0 in null-rotation) - True attitude quaternion component 3, y (0 in null-rotation) - True attitude quaternion component 4, z (0 in null-rotation) - Attitude roll expressed as Euler angles, not recommended except for human-readable outputs - Attitude pitch expressed as Euler angles, not recommended except for human-readable outputs - Attitude yaw expressed as Euler angles, not recommended except for human-readable outputs - X acceleration - Y acceleration - Z acceleration - Angular speed around X axis - Angular speed around Y axis - Angular speed around Z axis - Latitude (lower precision). Both this and the lat_int field should be set. - Longitude (lower precision). Both this and the lon_int field should be set. - Altitude - Horizontal position standard deviation - Vertical position standard deviation - True velocity in north direction in earth-fixed NED frame - True velocity in east direction in earth-fixed NED frame - True velocity in down direction in earth-fixed NED frame - - Latitude (higher precision). If 0, recipients should use the lat field value (otherwise this field is preferred). - Longitude (higher precision). If 0, recipients should use the lon field value (otherwise this field is preferred). - - - Status generated by radio and injected into MAVLink stream. - Local (message sender) received signal strength indication in device-dependent units/scale. Values: [0-254], UINT8_MAX: invalid/unknown. - Remote (message receiver) signal strength indication in device-dependent units/scale. Values: [0-254], UINT8_MAX: invalid/unknown. - Remaining free transmitter buffer space. - Local background noise level. These are device dependent RSSI values (scale as approx 2x dB on SiK radios). Values: [0-254], UINT8_MAX: invalid/unknown. - Remote background noise level. These are device dependent RSSI values (scale as approx 2x dB on SiK radios). Values: [0-254], UINT8_MAX: invalid/unknown. - Count of radio packet receive errors (since boot). - Count of error corrected radio packets (since boot). - - - File transfer protocol message: https://mavlink.io/en/services/ftp.html. - Network ID (0 for broadcast) - System ID (0 for broadcast) - Component ID (0 for broadcast) - Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The content/format of this block is defined in https://mavlink.io/en/services/ftp.html. - - - - Time synchronization message. - The message is used for both timesync requests and responses. - The request is sent with `ts1=syncing component timestamp` and `tc1=0`, and may be broadcast or targeted to a specific system/component. - The response is sent with `ts1=syncing component timestamp` (mirror back unchanged), and `tc1=responding component timestamp`, with the `target_system` and `target_component` set to ids of the original request. - Systems can determine if they are receiving a request or response based on the value of `tc`. - If the response has `target_system==target_component==0` the remote system has not been updated to use the component IDs and cannot reliably timesync; the requestor may report an error. - Timestamps are UNIX Epoch time or time since system boot in nanoseconds (the timestamp format can be inferred by checking for the magnitude of the number; generally it doesn't matter as only the offset is used). - The message sequence is repeated numerous times with results being filtered/averaged to estimate the offset. - - Time sync timestamp 1. Syncing: 0. Responding: Timestamp of responding component. - Time sync timestamp 2. Timestamp of syncing component (mirrored in response). - - Target system id. Request: 0 (broadcast) or id of specific system. Response must contain system id of the requesting component. - Target component id. Request: 0 (broadcast) or id of specific component. Response must contain component id of the requesting component. - - - Camera-IMU triggering and synchronisation message. - Timestamp for image frame (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - Image frame sequence - - - The global position, as returned by the Global Positioning System (GPS). This is - NOT the global position estimate of the system, but rather a RAW sensor value. See message GLOBAL_POSITION_INT for the global position estimate. - Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. - Latitude (WGS84) - Longitude (WGS84) - Altitude (MSL). Positive for up. - GPS HDOP horizontal dilution of position (unitless * 100). If unknown, set to: UINT16_MAX - GPS VDOP vertical dilution of position (unitless * 100). If unknown, set to: UINT16_MAX - GPS ground speed. If unknown, set to: UINT16_MAX - GPS velocity in north direction in earth-fixed NED frame - GPS velocity in east direction in earth-fixed NED frame - GPS velocity in down direction in earth-fixed NED frame - Course over ground (NOT heading, but direction of movement), 0.0..359.99 degrees. If unknown, set to: UINT16_MAX - Number of satellites visible. If unknown, set to UINT8_MAX - - GPS ID (zero indexed). Used for multiple GPS inputs - Yaw of vehicle relative to Earth's North, zero means not available, use 36000 for north - - - Simulated optical flow from a flow sensor (e.g. PX4FLOW or optical mouse sensor) - Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - Sensor ID - Integration time. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the. - Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.) - Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.) - RH rotation around X axis - RH rotation around Y axis - RH rotation around Z axis - Temperature - Optical flow quality / confidence. 0: no valid flow, 255: maximum quality - Time since the distance was sampled. - Distance to the center of the flow field. Positive value (including zero): distance known. Negative value: Unknown distance. - - - Sent from simulation to autopilot, avoids in contrast to HIL_STATE singularities. This packet is useful for high throughput applications such as hardware in the loop simulations. - Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - Vehicle attitude expressed as normalized quaternion in w, x, y, z order (with 1 0 0 0 being the null-rotation) - Body frame roll / phi angular speed - Body frame pitch / theta angular speed - Body frame yaw / psi angular speed - Latitude - Longitude - Altitude - Ground X Speed (Latitude) - Ground Y Speed (Longitude) - Ground Z Speed (Altitude) - Indicated airspeed - True airspeed - X acceleration - Y acceleration - Z acceleration - - - The RAW IMU readings for secondary 9DOF sensor setup. This message should contain the scaled values to the described units - Timestamp (time since system boot). - X acceleration - Y acceleration - Z acceleration - Angular speed around X axis - Angular speed around Y axis - Angular speed around Z axis - X Magnetic field - Y Magnetic field - Z Magnetic field - - Temperature, 0: IMU does not provide temperature values. If the IMU is at 0C it must send 1 (0.01C). - - - Request a list of available logs. On some systems calling this may stop on-board logging until LOG_REQUEST_END is called. If there are no log files available this request shall be answered with one LOG_ENTRY message with id = 0 and num_logs = 0. - System ID - Component ID - First log id (0 for first available) - Last log id (0xffff for last available) - - - Reply to LOG_REQUEST_LIST - Log id - Total number of logs - High log number - UTC timestamp of log since 1970, or 0 if not available - Size of the log (may be approximate) - - - Request a chunk of a log - System ID - Component ID - Log id (from LOG_ENTRY reply) - Offset into the log - Number of bytes - - - Reply to LOG_REQUEST_DATA - Log id (from LOG_ENTRY reply) - Offset into the log - Number of bytes (zero for end of log) - log data - - - Erase all logs - System ID - Component ID - - - Stop log transfer and resume normal logging - System ID - Component ID - - - - Data for injecting into the onboard GPS (used for DGPS) - System ID - Component ID - Data length - Raw data (110 is enough for 12 satellites of RTCMv2) - - - Second GPS data. - Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - GPS fix type. - Latitude (WGS84) - Longitude (WGS84) - Altitude (MSL). Positive for up. - GPS HDOP horizontal dilution of position (unitless * 100). If unknown, set to: UINT16_MAX - GPS VDOP vertical dilution of position (unitless * 100). If unknown, set to: UINT16_MAX - GPS ground speed. If unknown, set to: UINT16_MAX - Course over ground (NOT heading, but direction of movement): 0.0..359.99 degrees. If unknown, set to: UINT16_MAX - Number of satellites visible. If unknown, set to UINT8_MAX - Number of DGPS satellites - Age of DGPS info - - Yaw in earth frame from north. Use 0 if this GPS does not provide yaw. Use UINT16_MAX if this GPS is configured to provide yaw and is currently unable to provide it. Use 36000 for north. - Altitude (above WGS84, EGM96 ellipsoid). Positive for up. - Position uncertainty. - Altitude uncertainty. - Speed uncertainty. - Heading / track uncertainty - - - Power supply status - 5V rail voltage. - Servo rail voltage. - Bitmap of power supply status flags. - - - Control a serial port. This can be used for raw access to an onboard serial peripheral such as a GPS or telemetry radio. It is designed to make it possible to update the devices firmware via MAVLink messages or change the devices settings. A message with zero bytes can be used to change just the baudrate. - Serial control device type. - Bitmap of serial control flags. - Timeout for reply data - Baudrate of transfer. Zero means no change. - how many bytes in this transfer - serial data - - System ID - Component ID - - - RTK GPS data. Gives information on the relative baseline calculation the GPS is reporting - Time since boot of last baseline message received. - Identification of connected RTK receiver. - GPS Week Number of last baseline - GPS Time of Week of last baseline - GPS-specific health report for RTK data. - Rate of baseline messages being received by GPS - Current number of sats used for RTK calculation. - Coordinate system of baseline - Current baseline in ECEF x or NED north component. - Current baseline in ECEF y or NED east component. - Current baseline in ECEF z or NED down component. - Current estimate of baseline accuracy. - Current number of integer ambiguity hypotheses. - - - RTK GPS data. Gives information on the relative baseline calculation the GPS is reporting - Time since boot of last baseline message received. - Identification of connected RTK receiver. - GPS Week Number of last baseline - GPS Time of Week of last baseline - GPS-specific health report for RTK data. - Rate of baseline messages being received by GPS - Current number of sats used for RTK calculation. - Coordinate system of baseline - Current baseline in ECEF x or NED north component. - Current baseline in ECEF y or NED east component. - Current baseline in ECEF z or NED down component. - Current estimate of baseline accuracy. - Current number of integer ambiguity hypotheses. - - - The RAW IMU readings for 3rd 9DOF sensor setup. This message should contain the scaled values to the described units - Timestamp (time since system boot). - X acceleration - Y acceleration - Z acceleration - Angular speed around X axis - Angular speed around Y axis - Angular speed around Z axis - X Magnetic field - Y Magnetic field - Z Magnetic field - - Temperature, 0: IMU does not provide temperature values. If the IMU is at 0C it must send 1 (0.01C). - - - Handshake message to initiate, control and stop image streaming when using the Image Transmission Protocol: https://mavlink.io/en/services/image_transmission.html. - Type of requested/acknowledged data. - total data size (set on ACK only). - Width of a matrix or image. - Height of a matrix or image. - Number of packets being sent (set on ACK only). - Payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only). - JPEG quality. Values: [1-100]. - - - Data packet for images sent using the Image Transmission Protocol: https://mavlink.io/en/services/image_transmission.html. - sequence number (starting with 0 on every transmission) - image data bytes - - - Distance sensor information for an onboard rangefinder. - Timestamp (time since system boot). - Minimum distance the sensor can measure - Maximum distance the sensor can measure - Current distance reading - Type of distance sensor. - Onboard ID of the sensor - Direction the sensor faces. downward-facing: ROTATION_PITCH_270, upward-facing: ROTATION_PITCH_90, backward-facing: ROTATION_PITCH_180, forward-facing: ROTATION_NONE, left-facing: ROTATION_YAW_90, right-facing: ROTATION_YAW_270 - Measurement variance. Max standard deviation is 6cm. UINT8_MAX if unknown. - - Horizontal Field of View (angle) where the distance measurement is valid and the field of view is known. Otherwise this is set to 0. - Vertical Field of View (angle) where the distance measurement is valid and the field of view is known. Otherwise this is set to 0. - Quaternion of the sensor orientation in vehicle body frame (w, x, y, z order, zero-rotation is 1, 0, 0, 0). Zero-rotation is along the vehicle body x-axis. This field is required if the orientation is set to MAV_SENSOR_ROTATION_CUSTOM. Set it to 0 if invalid." - Signal quality of the sensor. Specific to each sensor type, representing the relation of the signal strength with the target reflectivity, distance, size or aspect, but normalised as a percentage. 0 = unknown/unset signal quality, 1 = invalid signal, 100 = perfect signal. - - - Request for terrain data and terrain status. See terrain protocol docs: https://mavlink.io/en/services/terrain.html - Latitude of SW corner of first grid - Longitude of SW corner of first grid - Grid spacing - Bitmask of requested 4x4 grids (row major 8x7 array of grids, 56 bits) - - - Terrain data sent from GCS. The lat/lon and grid_spacing must be the same as a lat/lon from a TERRAIN_REQUEST. See terrain protocol docs: https://mavlink.io/en/services/terrain.html - Latitude of SW corner of first grid - Longitude of SW corner of first grid - Grid spacing - bit within the terrain request mask - Terrain data MSL - - - Request that the vehicle report terrain height at the given location (expected response is a TERRAIN_REPORT). Used by GCS to check if vehicle has all terrain data needed for a mission. - Latitude - Longitude - - - Streamed from drone to report progress of terrain map download (initiated by TERRAIN_REQUEST), or sent as a response to a TERRAIN_CHECK request. See terrain protocol docs: https://mavlink.io/en/services/terrain.html - Latitude - Longitude - grid spacing (zero if terrain at this location unavailable) - Terrain height MSL - Current vehicle height above lat/lon terrain height - Number of 4x4 terrain blocks waiting to be received or read from disk - Number of 4x4 terrain blocks in memory - - - Barometer readings for 2nd barometer - Timestamp (time since system boot). - Absolute pressure - Differential pressure - Absolute pressure temperature - - Differential pressure temperature (0, if not available). Report values of 0 (or 1) as 1 cdegC. - - - Motion capture attitude and position - Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) - X position (NED) - Y position (NED) - Z position (NED) - - Row-major representation of a pose 6x6 cross-covariance matrix upper right triangle (states: x, y, z, roll, pitch, yaw; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array. - - - Set the vehicle attitude and body angular rates. - Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances. - System ID - Component ID - Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs. - - - Set the vehicle attitude and body angular rates. - Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances. - Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs. - - - The current system altitude. - Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - This altitude measure is initialized on system boot and monotonic (it is never reset, but represents the local altitude change). The only guarantee on this field is that it will never be reset and is consistent within a flight. The recommended value for this field is the uncorrected barometric altitude at boot time. This altitude will also drift and vary between flights. - This altitude measure is strictly above mean sea level and might be non-monotonic (it might reset on events like GPS lock or when a new QNH value is set). It should be the altitude to which global altitude waypoints are compared to. Note that it is *not* the GPS altitude, however, most GPS modules already output MSL by default and not the WGS84 altitude. - This is the local altitude in the local coordinate frame. It is not the altitude above home, but in reference to the coordinate origin (0, 0, 0). It is up-positive. - This is the altitude above the home position. It resets on each change of the current home position. - This is the altitude above terrain. It might be fed by a terrain database or an altimeter. Values smaller than -1000 should be interpreted as unknown. - This is not the altitude, but the clear space below the system according to the fused clearance estimate. It generally should max out at the maximum range of e.g. the laser altimeter. It is generally a moving target. A negative value indicates no measurement available. - - - The autopilot is requesting a resource (file, binary, other type of data) - Request ID. This ID should be re-used when sending back URI contents - The type of requested URI. 0 = a file via URL. 1 = a UAVCAN binary - The requested unique resource identifier (URI). It is not necessarily a straight domain name (depends on the URI type enum) - The way the autopilot wants to receive the URI. 0 = MAVLink FTP. 1 = binary stream. - The storage path the autopilot wants the URI to be stored in. Will only be valid if the transfer_type has a storage associated (e.g. MAVLink FTP). - - - Barometer readings for 3rd barometer - Timestamp (time since system boot). - Absolute pressure - Differential pressure - Absolute pressure temperature - - Differential pressure temperature (0, if not available). Report values of 0 (or 1) as 1 cdegC. - - - Current motion information from a designated system - Timestamp (time since system boot). - bit positions for tracker reporting capabilities (POS = 0, VEL = 1, ACCEL = 2, ATT + RATES = 3) - Latitude (WGS84) - Longitude (WGS84) - Altitude (MSL) - target velocity (0,0,0) for unknown - linear target acceleration (0,0,0) for unknown - (0 0 0 0 for unknown) - (0 0 0 for unknown) - eph epv - button states or switches of a tracker device - - - The smoothed, monotonic system state used to feed the control loops of the system. - Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - X acceleration in body frame - Y acceleration in body frame - Z acceleration in body frame - X velocity in body frame - Y velocity in body frame - Z velocity in body frame - X position in local frame - Y position in local frame - Z position in local frame - Airspeed, set to -1 if unknown - Variance of body velocity estimate - Variance in local position - The attitude, represented as Quaternion - Angular rate in roll axis - Angular rate in pitch axis - Angular rate in yaw axis - - - Battery information. Updates GCS with flight controller battery status. Smart batteries also use this message, but may additionally send SMART_BATTERY_INFO. - Battery ID - Function of the battery - Type (chemistry) of the battery - Temperature of the battery. INT16_MAX for unknown temperature. - Battery voltage of cells 1 to 10 (see voltages_ext for cells 11-14). Cells in this field above the valid cell count for this battery should have the UINT16_MAX value. If individual cell voltages are unknown or not measured for this battery, then the overall battery voltage should be filled in cell 0, with all others set to UINT16_MAX. If the voltage of the battery is greater than (UINT16_MAX - 1), then cell 0 should be set to (UINT16_MAX - 1), and cell 1 to the remaining voltage. This can be extended to multiple cells if the total voltage is greater than 2 * (UINT16_MAX - 1). - Battery current, -1: autopilot does not measure the current - Consumed charge, -1: autopilot does not provide consumption estimate - Consumed energy, -1: autopilot does not provide energy consumption estimate - Remaining battery energy. Values: [0-100], -1: autopilot does not estimate the remaining battery. - - Remaining battery time, 0: autopilot does not provide remaining battery time estimate - State for extent of discharge, provided by autopilot for warning or external reactions - Battery voltages for cells 11 to 14. Cells above the valid cell count for this battery should have a value of 0, where zero indicates not supported (note, this is different than for the voltages field and allows empty byte truncation). If the measured value is 0 then 1 should be sent instead. - Battery mode. Default (0) is that battery mode reporting is not supported or battery is in normal-use mode. - Fault/health indications. These should be set when charge_state is MAV_BATTERY_CHARGE_STATE_FAILED or MAV_BATTERY_CHARGE_STATE_UNHEALTHY (if not, fault reporting is not supported). - - - Version and capability of autopilot software. This should be emitted in response to a request with MAV_CMD_REQUEST_MESSAGE. - Bitmap of capabilities - Firmware version number - Middleware version number - Operating system version number - HW / board version (last 8 bits should be silicon ID, if any). The first 16 bits of this field specify https://github.com/PX4/PX4-Bootloader/blob/master/board_types.txt - Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. - Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. - Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases. - ID of the board vendor - ID of the product - UID if provided by hardware (see uid2) - - UID if provided by hardware (supersedes the uid field. If this is non-zero, use this field, otherwise use uid) - - - The location of a landing target. See: https://mavlink.io/en/services/landing_target.html - Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - The ID of the target if multiple targets are present - Coordinate frame used for following fields. - X-axis angular offset of the target from the center of the image - Y-axis angular offset of the target from the center of the image - Distance to the target from the vehicle - Size of target along x-axis - Size of target along y-axis - - X Position of the landing target in MAV_FRAME - Y Position of the landing target in MAV_FRAME - Z Position of the landing target in MAV_FRAME - Quaternion of landing target orientation (w, x, y, z order, zero-rotation is 1, 0, 0, 0) - Type of landing target - Boolean indicating whether the position fields (x, y, z, q, type) contain valid target position information (valid: 1, invalid: 0). Default is 0 (invalid). - - - - Status of geo-fencing. Sent in extended status stream when fencing enabled. - Breach status (0 if currently inside fence, 1 if outside). - Number of fence breaches. - Last breach type. - Time (since boot) of last breach. - - Active action to prevent fence breach - - - - - Reports results of completed compass calibration. Sent until MAG_CAL_ACK received. - Compass being calibrated. - Bitmask of compasses being calibrated. - Calibration Status. - 0=requires a MAV_CMD_DO_ACCEPT_MAG_CAL, 1=saved to parameters. - RMS milligauss residuals. - X offset. - Y offset. - Z offset. - X diagonal (matrix 11). - Y diagonal (matrix 22). - Z diagonal (matrix 33). - X off-diagonal (matrix 12 and 21). - Y off-diagonal (matrix 13 and 31). - Z off-diagonal (matrix 32 and 23). - - Confidence in orientation (higher is better). - orientation before calibration. - orientation after calibration. - field radius correction factor - - - - EFI status output - EFI health status - ECU index - RPM - Fuel consumed - Fuel flow rate - Engine load - Throttle position - Spark dwell time - Barometric pressure - Intake manifold pressure( - Intake manifold temperature - Cylinder head temperature - Ignition timing (Crank angle degrees) - Injection time - Exhaust gas temperature - Output throttle - Pressure/temperature compensation - - Supply voltage to EFI sparking system. Zero in this value means "unknown", so if the supply voltage really is zero volts use 0.0001 instead. - Fuel pressure. Zero in this value means "unknown", so if the fuel pressure really is zero kPa use 0.0001 instead. - - - - Estimator status message including flags, innovation test ratios and estimated accuracies. The flags message is an integer bitmask containing information on which EKF outputs are valid. See the ESTIMATOR_STATUS_FLAGS enum definition for further information. The innovation test ratios show the magnitude of the sensor innovation divided by the innovation check threshold. Under normal operation the innovation test ratios should be below 0.5 with occasional values up to 1.0. Values greater than 1.0 should be rare under normal operation and indicate that a measurement has been rejected by the filter. The user should be notified if an innovation test ratio greater than 1.0 is recorded. Notifications for values in the range between 0.5 and 1.0 should be optional and controllable by the user. - Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - Bitmap indicating which EKF outputs are valid. - Velocity innovation test ratio - Horizontal position innovation test ratio - Vertical position innovation test ratio - Magnetometer innovation test ratio - Height above terrain innovation test ratio - True airspeed innovation test ratio - Horizontal position 1-STD accuracy relative to the EKF local origin - Vertical position 1-STD accuracy relative to the EKF local origin - - - Wind estimate from vehicle. Note that despite the name, this message does not actually contain any covariances but instead variability and accuracy fields in terms of standard deviation (1-STD). - Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - Wind in North (NED) direction (NAN if unknown) - Wind in East (NED) direction (NAN if unknown) - Wind in down (NED) direction (NAN if unknown) - Variability of wind in XY, 1-STD estimated from a 1 Hz lowpassed wind estimate (NAN if unknown) - Variability of wind in Z, 1-STD estimated from a 1 Hz lowpassed wind estimate (NAN if unknown) - Altitude (MSL) that this measurement was taken at (NAN if unknown) - Horizontal speed 1-STD accuracy (0 if unknown) - Vertical speed 1-STD accuracy (0 if unknown) - - - GPS sensor input message. This is a raw sensor value sent by the GPS. This is NOT the global position estimate of the system. - Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - ID of the GPS for multiple GPS inputs - Bitmap indicating which GPS input flags fields to ignore. All other fields must be provided. - GPS time (from start of GPS week) - GPS week number - 0-1: no fix, 2: 2D fix, 3: 3D fix. 4: 3D with DGPS. 5: 3D with RTK - Latitude (WGS84) - Longitude (WGS84) - Altitude (MSL). Positive for up. - GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX - GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX - GPS velocity in north direction in earth-fixed NED frame - GPS velocity in east direction in earth-fixed NED frame - GPS velocity in down direction in earth-fixed NED frame - GPS speed accuracy - GPS horizontal accuracy - GPS vertical accuracy - Number of satellites visible. - - Yaw of vehicle relative to Earth's North, zero means not available, use 36000 for north - - - RTCM message for injecting into the onboard GPS (used for DGPS) - LSB: 1 means message is fragmented, next 2 bits are the fragment ID, the remaining 5 bits are used for the sequence ID. Messages are only to be flushed to the GPS when the entire message has been reconstructed on the autopilot. The fragment ID specifies which order the fragments should be assembled into a buffer, while the sequence ID is used to detect a mismatch between different buffers. The buffer is considered fully reconstructed when either all 4 fragments are present, or all the fragments before the first fragment with a non full payload is received. This management is used to ensure that normal GPS operation doesn't corrupt RTCM data, and to recover from a unreliable transport delivery order. - data length - RTCM message (may be fragmented) - - - - Message appropriate for high latency connections like Iridium - Bitmap of enabled system modes. - A bitfield for use for autopilot-specific flags. - The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown. - roll - pitch - heading - throttle (percentage) - heading setpoint - Latitude - Longitude - Altitude above mean sea level - Altitude setpoint relative to the home position - airspeed - airspeed setpoint - groundspeed - climb rate - Number of satellites visible. If unknown, set to UINT8_MAX - GPS Fix type. - Remaining battery (percentage) - Autopilot temperature (degrees C) - Air temperature (degrees C) from airspeed sensor - failsafe (each bit represents a failsafe where 0=ok, 1=failsafe active (bit0:RC, bit1:batt, bit2:GPS, bit3:GCS, bit4:fence) - current waypoint number - distance to target - - - Message appropriate for high latency connections like Iridium (version 2) - Timestamp (milliseconds since boot or Unix epoch) - Type of the MAV (quadrotor, helicopter, etc.) - Autopilot type / class. Use MAV_AUTOPILOT_INVALID for components that are not flight controllers. - A bitfield for use for autopilot-specific flags (2 byte version). - Latitude - Longitude - Altitude above mean sea level - Altitude setpoint - Heading - Heading setpoint - Distance to target waypoint or position - Throttle - Airspeed - Airspeed setpoint - Groundspeed - Windspeed - Wind heading - Maximum error horizontal position since last message - Maximum error vertical position since last message - Air temperature from airspeed sensor - Maximum climb rate magnitude since last message - Battery level (-1 if field not provided). - Current waypoint number - Bitmap of failure flags. - Field for custom payload. - Field for custom payload. - Field for custom payload. - - - Vibration levels and accelerometer clipping - Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - Vibration levels on X-axis - Vibration levels on Y-axis - Vibration levels on Z-axis - first accelerometer clipping count - second accelerometer clipping count - third accelerometer clipping count - - - - Contains the home position. - The home position is the default position that the system will return to and land on. - The position must be set automatically by the system during the takeoff, and may also be explicitly set using MAV_CMD_DO_SET_HOME. - The global and local positions encode the position in the respective coordinate frames, while the q parameter encodes the orientation of the surface. - Under normal conditions it describes the heading and terrain slope, which can be used by the aircraft to adjust the approach. - The approach 3D vector describes the point to which the system should fly in normal flight mode and then perform a landing sequence along the vector. - Note: this message can be requested by sending the MAV_CMD_REQUEST_MESSAGE with param1=242 (or the deprecated MAV_CMD_GET_HOME_POSITION command). - - Latitude (WGS84) - Longitude (WGS84) - Altitude (MSL). Positive for up. - Local X position of this position in the local coordinate frame (NED) - Local Y position of this position in the local coordinate frame (NED) - Local Z position of this position in the local coordinate frame (NED: positive "down") - - Quaternion indicating world-to-surface-normal and heading transformation of the takeoff position. - Used to indicate the heading and slope of the ground. - All fields should be set to NaN if an accurate quaternion for both heading and surface slope cannot be supplied. - - Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. - Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. - Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. - - Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - - - The command protocol version (MAV_CMD_DO_SET_HOME) allows a GCS to detect when setting the home position has failed. - - Sets the home position. - The home position is the default position that the system will return to and land on. - The position is set automatically by the system during the takeoff (and may also be set using this message). - The global and local positions encode the position in the respective coordinate frames, while the q parameter encodes the orientation of the surface. - Under normal conditions it describes the heading and terrain slope, which can be used by the aircraft to adjust the approach. - The approach 3D vector describes the point to which the system should fly in normal flight mode and then perform a landing sequence along the vector. - Note: the current home position may be emitted in a HOME_POSITION message on request (using MAV_CMD_REQUEST_MESSAGE with param1=242). - - System ID. - Latitude (WGS84) - Longitude (WGS84) - Altitude (MSL). Positive for up. - Local X position of this position in the local coordinate frame (NED) - Local Y position of this position in the local coordinate frame (NED) - Local Z position of this position in the local coordinate frame (NED: positive "down") - World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground - Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. - Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. - Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. - - Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - - - - The interval between messages for a particular MAVLink message ID. - This message is sent in response to the MAV_CMD_REQUEST_MESSAGE command with param1=244 (this message) and param2=message_id (the id of the message for which the interval is required). - It may also be sent in response to MAV_CMD_GET_MESSAGE_INTERVAL. - This interface replaces DATA_STREAM. - The ID of the requested MAVLink message. v1.0 is limited to 254 messages. - The interval between two messages. A value of -1 indicates this stream is disabled, 0 indicates it is not available, > 0 indicates the interval at which it is sent. - - - Provides state for additional features - The VTOL state if applicable. Is set to MAV_VTOL_STATE_UNDEFINED if UAV is not in VTOL configuration. - The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown. - - - The location and information of an ADSB vehicle - ICAO address - Latitude - Longitude - ADSB altitude type. - Altitude(ASL) - Course over ground - The horizontal velocity - The vertical velocity. Positive is up - The callsign, 8+null - ADSB emitter type. - Time since last communication in seconds - Bitmap to indicate various statuses including valid data fields - Squawk code - - - Information about a potential collision - Collision data source - Unique identifier, domain based on src field - Action that is being taken to avoid this collision - How concerned the aircraft is about this collision - Estimated time until collision occurs - Closest vertical distance between vehicle and object - Closest horizontal distance between vehicle and object - - - Message implementing parts of the V2 payload specs in V1 frames for transitional support. - Network ID (0 for broadcast) - System ID (0 for broadcast) - Component ID (0 for broadcast) - A code that identifies the software component that understands this message (analogous to USB device classes or mime type strings). If this code is less than 32768, it is considered a 'registered' protocol extension and the corresponding entry should be added to https://github.com/mavlink/mavlink/definition_files/extension_message_ids.xml. Software creators can register blocks of message IDs as needed (useful for GCS specific metadata, etc...). Message_types greater than 32767 are considered local experiments and should not be checked in to any widely distributed codebase. - Variable length payload. The length must be encoded in the payload as part of the message_type protocol, e.g. by including the length as payload data, or by terminating the payload data with a non-zero marker. This is required in order to reconstruct zero-terminated payloads that are (or otherwise would be) trimmed by MAVLink 2 empty-byte truncation. The entire content of the payload block is opaque unless you understand the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the MAVLink specification. - - - Send raw controller memory. The use of this message is discouraged for normal packets, but a quite efficient way for testing new messages and getting experimental debug output. - Starting address of the debug variables - Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below - Type code of the memory variables. for ver = 1: 0=16 x int16_t, 1=16 x uint16_t, 2=16 x Q15, 3=16 x 1Q14 - Memory contents at specified address - - - To debug something using a named 3D vector. - Name - Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - x - y - z - - - Send a key-value pair as float. The use of this message is discouraged for normal packets, but a quite efficient way for testing new messages and getting experimental debug output. - Timestamp (time since system boot). - Name of the debug variable - Floating point value - - - Send a key-value pair as integer. The use of this message is discouraged for normal packets, but a quite efficient way for testing new messages and getting experimental debug output. - Timestamp (time since system boot). - Name of the debug variable - Signed integer value - - - Status text message. These messages are printed in yellow in the COMM console of QGroundControl. WARNING: They consume quite some bandwidth, so use only for important status and error messages. If implemented wisely, these messages are buffered on the MCU and sent only at a limited rate (e.g. 10 Hz). - Severity of status. Relies on the definitions within RFC-5424. - Status text message, without null termination character - - Unique (opaque) identifier for this statustext message. May be used to reassemble a logical long-statustext message from a sequence of chunks. A value of zero indicates this is the only chunk in the sequence and the message can be emitted immediately. - This chunk's sequence number; indexing is from zero. Any null character in the text field is taken to mean this was the last chunk. - - - Send a debug value. The index is used to discriminate between values. These values show up in the plot of QGroundControl as DEBUG N. - Timestamp (time since system boot). - index of debug variable - DEBUG value - - - - Setup a MAVLink2 signing key. If called with secret_key of all zero and zero initial_timestamp will disable signing - system id of the target - component ID of the target - signing key - initial timestamp - - - Report button state change. - Timestamp (time since system boot). - Time of last change of button state. - Bitmap for state of buttons. - - - New version explicitly defines format. More interoperable. - Control vehicle tone generation (buzzer). - System ID - Component ID - tune in board specific format - - tune extension (appended to tune) - - - Information about a camera. Can be requested with a MAV_CMD_REQUEST_MESSAGE command. - Timestamp (time since system boot). - Name of the camera vendor - Name of the camera model - Version of the camera firmware, encoded as: (Dev & 0xff) << 24 | (Patch & 0xff) << 16 | (Minor & 0xff) << 8 | (Major & 0xff). Use 0 if not known. - Focal length. Use NaN if not known. - Image sensor size horizontal. Use NaN if not known. - Image sensor size vertical. Use NaN if not known. - Horizontal image resolution. Use 0 if not known. - Vertical image resolution. Use 0 if not known. - Reserved for a lens ID. Use 0 if not known. - Bitmap of camera capability flags. - Camera definition version (iteration). Use 0 if not known. - Camera definition URI (if any, otherwise only basic functions will be available). HTTP- (http://) and MAVLink FTP- (mavlinkftp://) formatted URIs are allowed (and both must be supported by any GCS that implements the Camera Protocol). The definition file may be xz compressed, which will be indicated by the file extension .xml.xz (a GCS that implements the protocol must support decompressing the file). The string needs to be zero terminated. Use a zero-length string if not known. - - Gimbal id of a gimbal associated with this camera. This is the component id of the gimbal device, or 1-6 for non mavlink gimbals. Use 0 if no gimbal is associated with the camera. - - - Settings of a camera. Can be requested with a MAV_CMD_REQUEST_MESSAGE command. - Timestamp (time since system boot). - Camera mode - - Current zoom level as a percentage of the full range (0.0 to 100.0, NaN if not known) - Current focus level as a percentage of the full range (0.0 to 100.0, NaN if not known) - - - Information about a storage medium. This message is sent in response to a request with MAV_CMD_REQUEST_MESSAGE and whenever the status of the storage changes (STORAGE_STATUS). Use MAV_CMD_REQUEST_MESSAGE.param2 to indicate the index/id of requested storage: 0 for all, 1 for first, 2 for second, etc. - Timestamp (time since system boot). - Storage ID (1 for first, 2 for second, etc.) - Number of storage devices - Status of storage - Total capacity. If storage is not ready (STORAGE_STATUS_READY) value will be ignored. - Used capacity. If storage is not ready (STORAGE_STATUS_READY) value will be ignored. - Available storage capacity. If storage is not ready (STORAGE_STATUS_READY) value will be ignored. - Read speed. - Write speed. - - Type of storage - Textual storage name to be used in UI (microSD 1, Internal Memory, etc.) This is a NULL terminated string. If it is exactly 32 characters long, add a terminating NULL. If this string is empty, the generic type is shown to the user. - Flags indicating whether this instance is preferred storage for photos, videos, etc. - Note: Implementations should initially set the flags on the system-default storage id used for saving media (if possible/supported). - This setting can then be overridden using MAV_CMD_SET_STORAGE_USAGE. - If the media usage flags are not set, a GCS may assume storage ID 1 is the default storage for all media types. - - - Information about the status of a capture. Can be requested with a MAV_CMD_REQUEST_MESSAGE command. - Timestamp (time since system boot). - Current status of image capturing (0: idle, 1: capture in progress, 2: interval set but idle, 3: interval set and capture in progress) - Current status of video capturing (0: idle, 1: capture in progress) - Image capture interval - Elapsed time since recording started (0: Not supported/available). A GCS should compute recording time and use non-zero values of this field to correct any discrepancy. - Available storage capacity. - - Total number of images captured ('forever', or until reset using MAV_CMD_STORAGE_FORMAT). - - - Information about a captured image. This is emitted every time a message is captured. - MAV_CMD_REQUEST_MESSAGE can be used to (re)request this message for a specific sequence number or range of sequence numbers: - MAV_CMD_REQUEST_MESSAGE.param2 indicates the sequence number the first image to send, or set to -1 to send the message for all sequence numbers. - MAV_CMD_REQUEST_MESSAGE.param3 is used to specify a range of messages to send: - set to 0 (default) to send just the the message for the sequence number in param 2, - set to -1 to send the message for the sequence number in param 2 and all the following sequence numbers, - set to the sequence number of the final message in the range. - Timestamp (time since system boot). - Timestamp (time since UNIX epoch) in UTC. 0 for unknown. - Deprecated/unused. Component IDs are used to differentiate multiple cameras. - Latitude where image was taken - Longitude where capture was taken - Altitude (MSL) where image was taken - Altitude above ground - Quaternion of camera orientation (w, x, y, z order, zero-rotation is 1, 0, 0, 0) - Zero based index of this image (i.e. a new image will have index CAMERA_CAPTURE_STATUS.image count -1) - Boolean indicating success (1) or failure (0) while capturing this image. - URL of image taken. Either local storage or http://foo.jpg if camera provides an HTTP interface. - - - Information about flight since last arming. - This can be requested using MAV_CMD_REQUEST_MESSAGE. - - Timestamp (time since system boot). - Timestamp at arming (time since UNIX epoch) in UTC, 0 for unknown - Timestamp at takeoff (time since UNIX epoch) in UTC, 0 for unknown - Universally unique identifier (UUID) of flight, should correspond to name of log files - - - This message is being superseded by MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW. The message can still be used to communicate with legacy gimbals implementing it. - Orientation of a mount - Timestamp (time since system boot). - Roll in global frame (set to NaN for invalid). - Pitch in global frame (set to NaN for invalid). - Yaw relative to vehicle (set to NaN for invalid). - - Yaw in absolute frame relative to Earth's North, north is 0 (set to NaN for invalid). - - - A message containing logged data (see also MAV_CMD_LOGGING_START) - system ID of the target - component ID of the target - sequence number (can wrap) - data length - offset into data where first message starts. This can be used for recovery, when a previous message got lost (set to UINT8_MAX if no start exists). - logged data - - - A message containing logged data which requires a LOGGING_ACK to be sent back - system ID of the target - component ID of the target - sequence number (can wrap) - data length - offset into data where first message starts. This can be used for recovery, when a previous message got lost (set to UINT8_MAX if no start exists). - logged data - - - An ack for a LOGGING_DATA_ACKED message - system ID of the target - component ID of the target - sequence number (must match the one in LOGGING_DATA_ACKED) - - - Information about video stream. It may be requested using MAV_CMD_REQUEST_MESSAGE, where param2 indicates the video stream id: 0 for all streams, 1 for first, 2 for second, etc. - Video Stream ID (1 for first, 2 for second, etc.) - Number of streams available. - Type of stream. - Bitmap of stream status flags. - Frame rate. - Horizontal resolution. - Vertical resolution. - Bit rate. - Video image rotation clockwise. - Horizontal Field of view. - Stream name. - Video stream URI (TCP or RTSP URI ground station should connect to) or port number (UDP port ground station should listen to). - - - Information about the status of a video stream. It may be requested using MAV_CMD_REQUEST_MESSAGE. - Video Stream ID (1 for first, 2 for second, etc.) - Bitmap of stream status flags - Frame rate - Horizontal resolution - Vertical resolution - Bit rate - Video image rotation clockwise - Horizontal Field of view - - - Information about the field of view of a camera. Can be requested with a MAV_CMD_REQUEST_MESSAGE command. - Timestamp (time since system boot). - Latitude of camera (INT32_MAX if unknown). - Longitude of camera (INT32_MAX if unknown). - Altitude (MSL) of camera (INT32_MAX if unknown). - Latitude of center of image (INT32_MAX if unknown, INT32_MIN if at infinity, not intersecting with horizon). - Longitude of center of image (INT32_MAX if unknown, INT32_MIN if at infinity, not intersecting with horizon). - Altitude (MSL) of center of image (INT32_MAX if unknown, INT32_MIN if at infinity, not intersecting with horizon). - Quaternion of camera orientation (w, x, y, z order, zero-rotation is 1, 0, 0, 0) - Horizontal field of view (NaN if unknown). - Vertical field of view (NaN if unknown). - - - Camera tracking status, sent while in active tracking. Use MAV_CMD_SET_MESSAGE_INTERVAL to define message interval. - Current tracking status - Current tracking mode - Defines location of target data - Current tracked point x value if CAMERA_TRACKING_MODE_POINT (normalized 0..1, 0 is left, 1 is right), NAN if unknown - Current tracked point y value if CAMERA_TRACKING_MODE_POINT (normalized 0..1, 0 is top, 1 is bottom), NAN if unknown - Current tracked radius if CAMERA_TRACKING_MODE_POINT (normalized 0..1, 0 is image left, 1 is image right), NAN if unknown - Current tracked rectangle top x value if CAMERA_TRACKING_MODE_RECTANGLE (normalized 0..1, 0 is left, 1 is right), NAN if unknown - Current tracked rectangle top y value if CAMERA_TRACKING_MODE_RECTANGLE (normalized 0..1, 0 is top, 1 is bottom), NAN if unknown - Current tracked rectangle bottom x value if CAMERA_TRACKING_MODE_RECTANGLE (normalized 0..1, 0 is left, 1 is right), NAN if unknown - Current tracked rectangle bottom y value if CAMERA_TRACKING_MODE_RECTANGLE (normalized 0..1, 0 is top, 1 is bottom), NAN if unknown - - - Camera tracking status, sent while in active tracking. Use MAV_CMD_SET_MESSAGE_INTERVAL to define message interval. - Current tracking status - Latitude of tracked object - Longitude of tracked object - Altitude of tracked object(AMSL, WGS84) - Horizontal accuracy. NAN if unknown - Vertical accuracy. NAN if unknown - North velocity of tracked object. NAN if unknown - East velocity of tracked object. NAN if unknown - Down velocity of tracked object. NAN if unknown - Velocity accuracy. NAN if unknown - Distance between camera and tracked object. NAN if unknown - Heading in radians, in NED. NAN if unknown - Accuracy of heading, in NED. NAN if unknown - - - Information about a high level gimbal manager. This message should be requested by a ground station using MAV_CMD_REQUEST_MESSAGE. - Timestamp (time since system boot). - Bitmap of gimbal capability flags. - Gimbal device ID that this gimbal manager is responsible for. Component ID of gimbal device (or 1-6 for non-MAVLink gimbal). - Minimum hardware roll angle (positive: rolling to the right, negative: rolling to the left) - Maximum hardware roll angle (positive: rolling to the right, negative: rolling to the left) - Minimum pitch angle (positive: up, negative: down) - Maximum pitch angle (positive: up, negative: down) - Minimum yaw angle (positive: to the right, negative: to the left) - Maximum yaw angle (positive: to the right, negative: to the left) - - - Current status about a high level gimbal manager. This message should be broadcast at a low regular rate (e.g. 5Hz). - Timestamp (time since system boot). - High level gimbal manager flags currently applied. - Gimbal device ID that this gimbal manager is responsible for. Component ID of gimbal device (or 1-6 for non-MAVLink gimbal). - System ID of MAVLink component with primary control, 0 for none. - Component ID of MAVLink component with primary control, 0 for none. - System ID of MAVLink component with secondary control, 0 for none. - Component ID of MAVLink component with secondary control, 0 for none. - - - High level message to control a gimbal's attitude. This message is to be sent to the gimbal manager (e.g. from a ground station). Angles and rates can be set to NaN according to use case. - System ID - Component ID - High level gimbal manager flags to use. - Component ID of gimbal device to address (or 1-6 for non-MAVLink gimbal), 0 for all gimbal device components. Send command multiple times for more than one gimbal (but not all gimbals). - Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation, the frame is depends on whether the flag GIMBAL_MANAGER_FLAGS_YAW_LOCK is set) - X component of angular velocity, positive is rolling to the right, NaN to be ignored. - Y component of angular velocity, positive is pitching up, NaN to be ignored. - Z component of angular velocity, positive is yawing to the right, NaN to be ignored. - - - Information about a low level gimbal. This message should be requested by the gimbal manager or a ground station using MAV_CMD_REQUEST_MESSAGE. The maximum angles and rates are the limits by hardware. However, the limits by software used are likely different/smaller and dependent on mode/settings/etc.. - Timestamp (time since system boot). - Name of the gimbal vendor. - Name of the gimbal model. - Custom name of the gimbal given to it by the user. - Version of the gimbal firmware, encoded as: (Dev & 0xff) << 24 | (Patch & 0xff) << 16 | (Minor & 0xff) << 8 | (Major & 0xff). - Version of the gimbal hardware, encoded as: (Dev & 0xff) << 24 | (Patch & 0xff) << 16 | (Minor & 0xff) << 8 | (Major & 0xff). - UID of gimbal hardware (0 if unknown). - Bitmap of gimbal capability flags. - Bitmap for use for gimbal-specific capability flags. - Minimum hardware roll angle (positive: rolling to the right, negative: rolling to the left). NAN if unknown. - Maximum hardware roll angle (positive: rolling to the right, negative: rolling to the left). NAN if unknown. - Minimum hardware pitch angle (positive: up, negative: down). NAN if unknown. - Maximum hardware pitch angle (positive: up, negative: down). NAN if unknown. - Minimum hardware yaw angle (positive: to the right, negative: to the left). NAN if unknown. - Maximum hardware yaw angle (positive: to the right, negative: to the left). NAN if unknown. - - This field is to be used if the gimbal manager and the gimbal device are the same component and hence have the same component ID. This field is then set to a number between 1-6. If the component ID is separate, this field is not required and must be set to 0. - - - Low level message to control a gimbal device's attitude. - This message is to be sent from the gimbal manager to the gimbal device component. - The quaternion and angular velocities can be set to NaN according to use case. - For the angles encoded in the quaternion and the angular velocities holds: - If the flag GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME is set, then they are relative to the vehicle heading (vehicle frame). - If the flag GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME is set, then they are relative to absolute North (earth frame). - If neither of these flags are set, then (for backwards compatibility) it holds: - If the flag GIMBAL_DEVICE_FLAGS_YAW_LOCK is set, then they are relative to absolute North (earth frame), - else they are relative to the vehicle heading (vehicle frame). - Setting both GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME and GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME is not allowed. - These rules are to ensure backwards compatibility. - New implementations should always set either GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME or GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME. - System ID - Component ID - Low level gimbal flags. - Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation). The frame is described in the message description. Set fields to NaN to be ignored. - X component of angular velocity (positive: rolling to the right). The frame is described in the message description. NaN to be ignored. - Y component of angular velocity (positive: pitching up). The frame is described in the message description. NaN to be ignored. - Z component of angular velocity (positive: yawing to the right). The frame is described in the message description. NaN to be ignored. - - - Message reporting the status of a gimbal device. - This message should be broadcast by a gimbal device component at a low regular rate (e.g. 5 Hz). - For the angles encoded in the quaternion and the angular velocities holds: - If the flag GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME is set, then they are relative to the vehicle heading (vehicle frame). - If the flag GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME is set, then they are relative to absolute North (earth frame). - If neither of these flags are set, then (for backwards compatibility) it holds: - If the flag GIMBAL_DEVICE_FLAGS_YAW_LOCK is set, then they are relative to absolute North (earth frame), - else they are relative to the vehicle heading (vehicle frame). - Other conditions of the flags are not allowed. - The quaternion and angular velocities in the other frame can be calculated from delta_yaw and delta_yaw_velocity as - q_earth = q_delta_yaw * q_vehicle and w_earth = w_delta_yaw_velocity + w_vehicle (if not NaN). - If neither the GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME nor the GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME flag is set, - then (for backwards compatibility) the data in the delta_yaw and delta_yaw_velocity fields are to be ignored. - New implementations should always set either GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME or GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME, - and always should set delta_yaw and delta_yaw_velocity either to the proper value or NaN. - System ID - Component ID - Timestamp (time since system boot). - Current gimbal flags set. - Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation). The frame is described in the message description. - X component of angular velocity (positive: rolling to the right). The frame is described in the message description. NaN if unknown. - Y component of angular velocity (positive: pitching up). The frame is described in the message description. NaN if unknown. - Z component of angular velocity (positive: yawing to the right). The frame is described in the message description. NaN if unknown. - Failure flags (0 for no failure) - - Yaw angle relating the quaternions in earth and body frames (see message description). NaN if unknown. - Yaw angular velocity relating the angular velocities in earth and body frames (see message description). NaN if unknown. - This field is to be used if the gimbal manager and the gimbal device are the same component and hence have the same component ID. This field is then set a number between 1-6. If the component ID is separate, this field is not required and must be set to 0. - - - Low level message containing autopilot state relevant for a gimbal device. This message is to be sent from the autopilot to the gimbal device component. The data of this message are for the gimbal device's estimator corrections, in particular horizon compensation, as well as indicates autopilot control intentions, e.g. feed forward angular control in the z-axis. - System ID - Component ID - Timestamp (time since system boot). - Quaternion components of autopilot attitude: w, x, y, z (1 0 0 0 is the null-rotation, Hamilton convention). - Estimated delay of the attitude data. 0 if unknown. - X Speed in NED (North, East, Down). NAN if unknown. - Y Speed in NED (North, East, Down). NAN if unknown. - Z Speed in NED (North, East, Down). NAN if unknown. - Estimated delay of the speed data. 0 if unknown. - Feed forward Z component of angular velocity (positive: yawing to the right). NaN to be ignored. This is to indicate if the autopilot is actively yawing. - Bitmap indicating which estimator outputs are valid. - The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown. - - Z component of angular velocity in NED (North, East, Down). NaN if unknown. - - - Set gimbal manager pitch and yaw angles (high rate message). This message is to be sent to the gimbal manager (e.g. from a ground station) and will be ignored by gimbal devices. Angles and rates can be set to NaN according to use case. Use MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW for low-rate adjustments that require confirmation. - System ID - Component ID - High level gimbal manager flags to use. - Component ID of gimbal device to address (or 1-6 for non-MAVLink gimbal), 0 for all gimbal device components. Send command multiple times for more than one gimbal (but not all gimbals). - Pitch angle (positive: up, negative: down, NaN to be ignored). - Yaw angle (positive: to the right, negative: to the left, NaN to be ignored). - Pitch angular rate (positive: up, negative: down, NaN to be ignored). - Yaw angular rate (positive: to the right, negative: to the left, NaN to be ignored). - - - High level message to control a gimbal manually. The angles or angular rates are unitless; the actual rates will depend on internal gimbal manager settings/configuration (e.g. set by parameters). This message is to be sent to the gimbal manager (e.g. from a ground station). Angles and rates can be set to NaN according to use case. - System ID - Component ID - High level gimbal manager flags. - Component ID of gimbal device to address (or 1-6 for non-MAVLink gimbal), 0 for all gimbal device components. Send command multiple times for more than one gimbal (but not all gimbals). - Pitch angle unitless (-1..1, positive: up, negative: down, NaN to be ignored). - Yaw angle unitless (-1..1, positive: to the right, negative: to the left, NaN to be ignored). - Pitch angular rate unitless (-1..1, positive: up, negative: down, NaN to be ignored). - Yaw angular rate unitless (-1..1, positive: to the right, negative: to the left, NaN to be ignored). - - - - - ESC information for lower rate streaming. Recommended streaming rate 1Hz. See ESC_STATUS for higher-rate ESC data. - Index of the first ESC in this message. minValue = 0, maxValue = 60, increment = 4. - Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude the number. - Counter of data packets received. - Total number of ESCs in all messages of this type. Message fields with an index higher than this should be ignored because they contain invalid data. - Connection type protocol for all ESC. - Information regarding online/offline status of each ESC. - Bitmap of ESC failure flags. - Number of reported errors by each ESC since boot. - Temperature of each ESC. INT16_MAX: if data not supplied by ESC. - - - - - ESC information for higher rate streaming. Recommended streaming rate is ~10 Hz. Information that changes more slowly is sent in ESC_INFO. It should typically only be streamed on high-bandwidth links (i.e. to a companion computer). - Index of the first ESC in this message. minValue = 0, maxValue = 60, increment = 4. - Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude the number. - Reported motor RPM from each ESC (negative for reverse rotation). - Voltage measured from each ESC. - Current measured from each ESC. - - - - Configure WiFi AP SSID, password, and mode. This message is re-emitted as an acknowledgement by the AP. The message may also be explicitly requested using MAV_CMD_REQUEST_MESSAGE - Name of Wi-Fi network (SSID). Blank to leave it unchanged when setting. Current SSID when sent back as a response. - Password. Blank for an open AP. MD5 hash when message is sent back as a response. - - WiFi Mode. - Message acceptance response (sent back to GS). - - - The location and information of an AIS vessel - Mobile Marine Service Identifier, 9 decimal digits - Latitude - Longitude - Course over ground - True heading - Speed over ground - Turn rate - Navigational status - Type of vessels - Distance from lat/lon location to bow - Distance from lat/lon location to stern - Distance from lat/lon location to port side - Distance from lat/lon location to starboard side - The vessel callsign - The vessel name - Time since last communication in seconds - Bitmask to indicate various statuses including valid data fields - - - - General status information of an UAVCAN node. Please refer to the definition of the UAVCAN message "uavcan.protocol.NodeStatus" for the background information. The UAVCAN specification is available at http://uavcan.org. - Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - Time since the start-up of the node. - Generalized node health status. - Generalized operating mode. - Not used currently. - Vendor-specific status information. - - - General information describing a particular UAVCAN node. Please refer to the definition of the UAVCAN service "uavcan.protocol.GetNodeInfo" for the background information. This message should be emitted by the system whenever a new node appears online, or an existing node reboots. Additionally, it can be emitted upon request from the other end of the MAVLink channel (see MAV_CMD_UAVCAN_GET_NODE_INFO). It is also not prohibited to emit this message unconditionally at a low frequency. The UAVCAN specification is available at http://uavcan.org. - Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - Time since the start-up of the node. - Node name string. For example, "sapog.px4.io". - Hardware major version number. - Hardware minor version number. - Hardware unique 128-bit ID. - Software major version number. - Software minor version number. - Version control system (VCS) revision identifier (e.g. git short commit hash). 0 if unknown. - - - Request to read the value of a parameter with either the param_id string id or param_index. PARAM_EXT_VALUE should be emitted in response. - System ID - Component ID - Parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string - Parameter index. Set to -1 to use the Parameter ID field as identifier (else param_id will be ignored) - - - Request all parameters of this component. All parameters should be emitted in response as PARAM_EXT_VALUE. - System ID - Component ID - - - Emit the value of a parameter. The inclusion of param_count and param_index in the message allows the recipient to keep track of received parameters and allows them to re-request missing parameters after a loss or timeout. - Parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string - Parameter value - Parameter type. - Total number of parameters - Index of this parameter - - - Set a parameter value. In order to deal with message loss (and retransmission of PARAM_EXT_SET), when setting a parameter value and the new value is the same as the current value, you will immediately get a PARAM_ACK_ACCEPTED response. If the current state is PARAM_ACK_IN_PROGRESS, you will accordingly receive a PARAM_ACK_IN_PROGRESS in response. - System ID - Component ID - Parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string - Parameter value - Parameter type. - - - Response from a PARAM_EXT_SET message. - Parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string - Parameter value (new value if PARAM_ACK_ACCEPTED, current value otherwise) - Parameter type. - Result code. - - - Obstacle distances in front of the sensor, starting from the left in increment degrees to the right - Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - Class id of the distance sensor type. - Distance of obstacles around the vehicle with index 0 corresponding to north + angle_offset, unless otherwise specified in the frame. A value of 0 is valid and means that the obstacle is practically touching the sensor. A value of max_distance +1 means no obstacle is present. A value of UINT16_MAX for unknown/not used. In a array element, one unit corresponds to 1cm. - Angular width in degrees of each array element. Increment direction is clockwise. This field is ignored if increment_f is non-zero. - Minimum distance the sensor can measure. - Maximum distance the sensor can measure. - - Angular width in degrees of each array element as a float. If non-zero then this value is used instead of the uint8_t increment field. Positive is clockwise direction, negative is counter-clockwise. - Relative angle offset of the 0-index element in the distances array. Value of 0 corresponds to forward. Positive is clockwise direction, negative is counter-clockwise. - Coordinate frame of reference for the yaw rotation and offset of the sensor data. Defaults to MAV_FRAME_GLOBAL, which is north aligned. For body-mounted sensors use MAV_FRAME_BODY_FRD, which is vehicle front aligned. - - - Odometry message to communicate odometry information with an external interface. Fits ROS REP 147 standard for aerial vehicles (http://www.ros.org/reps/rep-0147.html). - Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - Coordinate frame of reference for the pose data. - Coordinate frame of reference for the velocity in free space (twist) data. - X Position - Y Position - Z Position - Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation) - X linear speed - Y linear speed - Z linear speed - Roll angular speed - Pitch angular speed - Yaw angular speed - Row-major representation of a 6x6 pose cross-covariance matrix upper right triangle (states: x, y, z, roll, pitch, yaw; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array. - Row-major representation of a 6x6 velocity cross-covariance matrix upper right triangle (states: vx, vy, vz, rollspeed, pitchspeed, yawspeed; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array. - - Estimate reset counter. This should be incremented when the estimate resets in any of the dimensions (position, velocity, attitude, angular speed). This is designed to be used when e.g an external SLAM system detects a loop-closure and the estimate jumps. - Type of estimator that is providing the odometry. - Optional odometry quality metric as a percentage. -1 = odometry has failed, 0 = unknown/unset quality, 1 = worst quality, 100 = best quality - - - Describe a trajectory using an array of up-to 5 waypoints in the local frame (MAV_FRAME_LOCAL_NED). - Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - Number of valid points (up-to 5 waypoints are possible) - X-coordinate of waypoint, set to NaN if not being used - Y-coordinate of waypoint, set to NaN if not being used - Z-coordinate of waypoint, set to NaN if not being used - X-velocity of waypoint, set to NaN if not being used - Y-velocity of waypoint, set to NaN if not being used - Z-velocity of waypoint, set to NaN if not being used - X-acceleration of waypoint, set to NaN if not being used - Y-acceleration of waypoint, set to NaN if not being used - Z-acceleration of waypoint, set to NaN if not being used - Yaw angle, set to NaN if not being used - Yaw rate, set to NaN if not being used - MAV_CMD command id of waypoint, set to UINT16_MAX if not being used. - - - Describe a trajectory using an array of up-to 5 bezier control points in the local frame (MAV_FRAME_LOCAL_NED). - Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - Number of valid control points (up-to 5 points are possible) - X-coordinate of bezier control points. Set to NaN if not being used - Y-coordinate of bezier control points. Set to NaN if not being used - Z-coordinate of bezier control points. Set to NaN if not being used - Bezier time horizon. Set to NaN if velocity/acceleration should not be incorporated - Yaw. Set to NaN for unchanged - - - - Report current used cellular network status - Cellular modem status - Failure reason when status in in CELLULAR_STATUS_FLAG_FAILED - Cellular network radio type: gsm, cdma, lte... - Signal quality in percent. If unknown, set to UINT8_MAX - Mobile country code. If unknown, set to UINT16_MAX - Mobile network code. If unknown, set to UINT16_MAX - Location area code. If unknown, set to 0 - - - Status of the Iridium SBD link. - Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - Timestamp of the last successful sbd session. The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - Number of failed SBD sessions. - Number of successful SBD sessions. - Signal quality equal to the number of bars displayed on the ISU signal strength indicator. Range is 0 to 5, where 0 indicates no signal and 5 indicates maximum signal strength. - 1: Ring call pending, 0: No call pending. - 1: Transmission session pending, 0: No transmission session pending. - 1: Receiving session pending, 0: No receiving session pending. - - - Configure cellular modems. - This message is re-emitted as an acknowledgement by the modem. - The message may also be explicitly requested using MAV_CMD_REQUEST_MESSAGE. - Enable/disable LTE. 0: setting unchanged, 1: disabled, 2: enabled. Current setting when sent back as a response. - Enable/disable PIN on the SIM card. 0: setting unchanged, 1: disabled, 2: enabled. Current setting when sent back as a response. - PIN sent to the SIM card. Blank when PIN is disabled. Empty when message is sent back as a response. - New PIN when changing the PIN. Blank to leave it unchanged. Empty when message is sent back as a response. - Name of the cellular APN. Blank to leave it unchanged. Current APN when sent back as a response. - Required PUK code in case the user failed to authenticate 3 times with the PIN. Empty when message is sent back as a response. - Enable/disable roaming. 0: setting unchanged, 1: disabled, 2: enabled. Current setting when sent back as a response. - Message acceptance response (sent back to GS). - - - RPM sensor data message. - Index of this RPM sensor (0-indexed) - Indicated rate - - - The global position resulting from GPS and sensor fusion. - Time of applicability of position (microseconds since UNIX epoch). - Unique UAS ID. - Latitude (WGS84) - Longitude (WGS84) - Altitude (WGS84) - Altitude above ground - Ground X speed (latitude, positive north) - Ground Y speed (longitude, positive east) - Ground Z speed (altitude, positive down) - Horizontal position uncertainty (standard deviation) - Altitude uncertainty (standard deviation) - Speed uncertainty (standard deviation) - Next waypoint, latitude (WGS84) - Next waypoint, longitude (WGS84) - Next waypoint, altitude (WGS84) - Time until next update. Set to 0 if unknown or in data driven mode. - Flight state - Bitwise OR combination of the data available flags. - - - Large debug/prototyping array. The message uses the maximum available payload for data. The array_id and name fields are used to discriminate between messages in code and in user interfaces (respectively). Do not use in production code. - Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - Name, for human-friendly display in a Ground Control Station - Unique ID used to discriminate between arrays - - data - - - - - Vehicle status report that is sent out while orbit execution is in progress (see MAV_CMD_DO_ORBIT). - Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - Radius of the orbit circle. Positive values orbit clockwise, negative values orbit counter-clockwise. - The coordinate system of the fields: x, y, z. - X coordinate of center point. Coordinate system depends on frame field: local = x position in meters * 1e4, global = latitude in degrees * 1e7. - Y coordinate of center point. Coordinate system depends on frame field: local = x position in meters * 1e4, global = latitude in degrees * 1e7. - Altitude of center point. Coordinate system depends on frame field. - - - Smart Battery information (static/infrequent update). Use for updates from: smart battery to flight stack, flight stack to GCS. Use BATTERY_STATUS for smart battery frequent updates. - Battery ID - Function of the battery - Type (chemistry) of the battery - Capacity when full according to manufacturer, -1: field not provided. - Capacity when full (accounting for battery degradation), -1: field not provided. - Charge/discharge cycle count. UINT16_MAX: field not provided. - Serial number in ASCII characters, 0 terminated. All 0: field not provided. - Static device name in ASCII characters, 0 terminated. All 0: field not provided. Encode as manufacturer name then product name separated using an underscore. - Battery weight. 0: field not provided. - Minimum per-cell voltage when discharging. If not supplied set to UINT16_MAX value. - Minimum per-cell voltage when charging. If not supplied set to UINT16_MAX value. - Minimum per-cell voltage when resting. If not supplied set to UINT16_MAX value. - - Maximum per-cell voltage when charged. 0: field not provided. - Number of battery cells in series. 0: field not provided. - Maximum pack discharge current. 0: field not provided. - Maximum pack discharge burst current. 0: field not provided. - Manufacture date (DD/MM/YYYY) in ASCII characters, 0 terminated. All 0: field not provided. - - - Telemetry of power generation system. Alternator or mechanical generator. - Status flags. - Speed of electrical generator or alternator. UINT16_MAX: field not provided. - Current into/out of battery. Positive for out. Negative for in. NaN: field not provided. - Current going to the UAV. If battery current not available this is the DC current from the generator. Positive for out. Negative for in. NaN: field not provided - The power being generated. NaN: field not provided - Voltage of the bus seen at the generator, or battery bus if battery bus is controlled by generator and at a different voltage to main bus. - The temperature of the rectifier or power converter. INT16_MAX: field not provided. - The target battery current. Positive for out. Negative for in. NaN: field not provided - The temperature of the mechanical motor, fuel cell core or generator. INT16_MAX: field not provided. - Seconds this generator has run since it was rebooted. UINT32_MAX: field not provided. - Seconds until this generator requires maintenance. A negative value indicates maintenance is past-due. INT32_MAX: field not provided. - - - The raw values of the actuator outputs (e.g. on Pixhawk, from MAIN, AUX ports). This message supersedes SERVO_OUTPUT_RAW. - Timestamp (since system boot). - Active outputs - Servo / motor output array values. Zero values indicate unused channels. - - - - - Time/duration estimates for various events and actions given the current vehicle state and position. - Estimated time to complete the vehicle's configured "safe return" action from its current position (e.g. RTL, Smart RTL, etc.). -1 indicates that the vehicle is landed, or that no time estimate available. - Estimated time for vehicle to complete the LAND action from its current position. -1 indicates that the vehicle is landed, or that no time estimate available. - Estimated time for reaching/completing the currently active mission item. -1 means no time estimate available. - Estimated time for completing the current mission. -1 means no mission active and/or no estimate available. - Estimated time for completing the current commanded action (i.e. Go To, Takeoff, Land, etc.). -1 means no action active and/or no estimate available. - - - Message for transporting "arbitrary" variable-length data from one component to another (broadcast is not forbidden, but discouraged). The encoding of the data is usually extension specific, i.e. determined by the source, and is usually not documented as part of the MAVLink specification. - System ID (can be 0 for broadcast, but this is discouraged) - Component ID (can be 0 for broadcast, but this is discouraged) - A code that identifies the content of the payload (0 for unknown, which is the default). If this code is less than 32768, it is a 'registered' payload type and the corresponding code should be added to the MAV_TUNNEL_PAYLOAD_TYPE enum. Software creators can register blocks of types as needed. Codes greater than 32767 are considered local experiments and should not be checked in to any widely distributed codebase. - Length of the data transported in payload - Variable length payload. The payload length is defined by payload_length. The entire content of this block is opaque unless you understand the encoding specified by payload_type. - - - A forwarded CAN frame as requested by MAV_CMD_CAN_FORWARD. - System ID. - Component ID. - Bus number - Frame length - Frame ID - Frame data - - - - - Hardware status sent by an onboard computer. - Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - Time since system boot. - Type of the onboard computer: 0: Mission computer primary, 1: Mission computer backup 1, 2: Mission computer backup 2, 3: Compute node, 4-5: Compute spares, 6-9: Payload computers. - CPU usage on the component in percent (100 - idle). A value of UINT8_MAX implies the field is unused. - Combined CPU usage as the last 10 slices of 100 MS (a histogram). This allows to identify spikes in load that max out the system, but only for a short amount of time. A value of UINT8_MAX implies the field is unused. - GPU usage on the component in percent (100 - idle). A value of UINT8_MAX implies the field is unused. - Combined GPU usage as the last 10 slices of 100 MS (a histogram). This allows to identify spikes in load that max out the system, but only for a short amount of time. A value of UINT8_MAX implies the field is unused. - Temperature of the board. A value of INT8_MAX implies the field is unused. - Temperature of the CPU core. A value of INT8_MAX implies the field is unused. - Fan speeds. A value of INT16_MAX implies the field is unused. - Amount of used RAM on the component system. A value of UINT32_MAX implies the field is unused. - Total amount of RAM on the component system. A value of UINT32_MAX implies the field is unused. - Storage type: 0: HDD, 1: SSD, 2: EMMC, 3: SD card (non-removable), 4: SD card (removable). A value of UINT32_MAX implies the field is unused. - Amount of used storage space on the component system. A value of UINT32_MAX implies the field is unused. - Total amount of storage space on the component system. A value of UINT32_MAX implies the field is unused. - Link type: 0-9: UART, 10-19: Wired network, 20-29: Wifi, 30-39: Point-to-point proprietary, 40-49: Mesh proprietary - Network traffic from the component system. A value of UINT32_MAX implies the field is unused. - Network traffic to the component system. A value of UINT32_MAX implies the field is unused. - Network capacity from the component system. A value of UINT32_MAX implies the field is unused. - Network capacity to the component system. A value of UINT32_MAX implies the field is unused. - - - - - Component information message, which may be requested using MAV_CMD_REQUEST_MESSAGE. - - Timestamp (time since system boot). - CRC32 of the general metadata file (general_metadata_uri). - MAVLink FTP URI for the general metadata file (COMP_METADATA_TYPE_GENERAL), which may be compressed with xz. The file contains general component metadata, and may contain URI links for additional metadata (see COMP_METADATA_TYPE). The information is static from boot, and may be generated at compile time. The string needs to be zero terminated. - CRC32 of peripherals metadata file (peripherals_metadata_uri). - (Optional) MAVLink FTP URI for the peripherals metadata file (COMP_METADATA_TYPE_PERIPHERALS), which may be compressed with xz. This contains data about "attached components" such as UAVCAN nodes. The peripherals are in a separate file because the information must be generated dynamically at runtime. The string needs to be zero terminated. - - - - - - Component metadata message, which may be requested using MAV_CMD_REQUEST_MESSAGE. - - This contains the MAVLink FTP URI and CRC for the component's general metadata file. - The file must be hosted on the component, and may be xz compressed. - The file CRC can be used for file caching. - - The general metadata file can be read to get the locations of other metadata files (COMP_METADATA_TYPE) and translations, which may be hosted either on the vehicle or the internet. - For more information see: https://mavlink.io/en/services/component_information.html. - - Note: Camera components should use CAMERA_INFORMATION instead, and autopilots may use both this message and AUTOPILOT_VERSION. - - Timestamp (time since system boot). - CRC32 of the general metadata file. - MAVLink FTP URI for the general metadata file (COMP_METADATA_TYPE_GENERAL), which may be compressed with xz. The file contains general component metadata, and may contain URI links for additional metadata (see COMP_METADATA_TYPE). The information is static from boot, and may be generated at compile time. The string needs to be zero terminated. - - - Play vehicle tone/tune (buzzer). Supersedes message PLAY_TUNE. - System ID - Component ID - Tune format - Tune definition as a NULL-terminated string. - - - Tune formats supported by vehicle. This should be emitted as response to MAV_CMD_REQUEST_MESSAGE. - System ID - Component ID - Bitfield of supported tune formats. - - - - - - Event message. Each new event from a particular component gets a new sequence number. The same message might be sent multiple times if (re-)requested. Most events are broadcast, some can be specific to a target component (as receivers keep track of the sequence for missed events, all events need to be broadcast. Thus we use destination_component instead of target_component). - Component ID - System ID - Event ID (as defined in the component metadata) - Timestamp (time since system boot when the event happened). - Sequence number. - Log levels: 4 bits MSB: internal (for logging purposes), 4 bits LSB: external. Levels: Emergency = 0, Alert = 1, Critical = 2, Error = 3, Warning = 4, Notice = 5, Info = 6, Debug = 7, Protocol = 8, Disabled = 9 - Arguments (depend on event ID). - - - - - Regular broadcast for the current latest event sequence number for a component. This is used to check for dropped events. - Sequence number. - Flag bitset. - - - - - Request one or more events to be (re-)sent. If first_sequence==last_sequence, only a single event is requested. Note that first_sequence can be larger than last_sequence (because the sequence number can wrap). Each sequence will trigger an EVENT or EVENT_ERROR response. - System ID - Component ID - First sequence number of the requested event. - Last sequence number of the requested event. - - - - - Response to a REQUEST_EVENT in case of an error (e.g. the event is not available anymore). - System ID - Component ID - Sequence number. - Oldest Sequence number that is still available after the sequence set in REQUEST_EVENT. - Error reason. - - - - A forwarded CANFD frame as requested by MAV_CMD_CAN_FORWARD. These are separated from CAN_FRAME as they need different handling (eg. TAO handling) - System ID. - Component ID. - bus number - Frame length - Frame ID - Frame data - - - Modify the filter of what CAN messages to forward over the mavlink. This can be used to make CAN forwarding work well on low bandwidth links. The filtering is applied on bits 8 to 24 of the CAN id (2nd and 3rd bytes) which corresponds to the DroneCAN message ID for DroneCAN. Filters with more than 16 IDs can be constructed by sending multiple CAN_FILTER_MODIFY messages. - System ID. - Component ID. - bus number - what operation to perform on the filter list. See CAN_FILTER_OP enum. - number of IDs in filter list - filter IDs, length num_ids - - - - Cumulative distance traveled for each reported wheel. - Timestamp (synced to UNIX time or since system boot). - Number of wheels reported. - Distance reported by individual wheel encoders. Forward rotations increase values, reverse rotations decrease them. Not all wheels will necessarily have wheel encoders; the mapping of encoders to wheel positions must be agreed/understood by the endpoints. - - - Winch status. - Timestamp (synced to UNIX time or since system boot). - Length of line released. NaN if unknown - Speed line is being released or retracted. Positive values if being released, negative values if being retracted, NaN if unknown - Tension on the line. NaN if unknown - Voltage of the battery supplying the winch. NaN if unknown - Current draw from the winch. NaN if unknown - Temperature of the motor. INT16_MAX if unknown - Status flags - - - Data for filling the OpenDroneID Basic ID message. This and the below messages are primarily meant for feeding data to/from an OpenDroneID implementation. E.g. https://github.com/opendroneid/opendroneid-core-c. These messages are compatible with the ASTM F3411 Remote ID standard and the ASD-STAN prEN 4709-002 Direct Remote ID standard. Additional information and usage of these messages is documented at https://mavlink.io/en/services/opendroneid.html. - System ID (0 for broadcast). - Component ID (0 for broadcast). - Only used for drone ID data received from other UAs. See detailed description at https://mavlink.io/en/services/opendroneid.html. - Indicates the format for the uas_id field of this message. - Indicates the type of UA (Unmanned Aircraft). - UAS (Unmanned Aircraft System) ID following the format specified by id_type. Shall be filled with nulls in the unused portion of the field. - - - Data for filling the OpenDroneID Location message. The float data types are 32-bit IEEE 754. The Location message provides the location, altitude, direction and speed of the aircraft. - System ID (0 for broadcast). - Component ID (0 for broadcast). - Only used for drone ID data received from other UAs. See detailed description at https://mavlink.io/en/services/opendroneid.html. - Indicates whether the unmanned aircraft is on the ground or in the air. - Direction over ground (not heading, but direction of movement) measured clockwise from true North: 0 - 35999 centi-degrees. If unknown: 36100 centi-degrees. - Ground speed. Positive only. If unknown: 25500 cm/s. If speed is larger than 25425 cm/s, use 25425 cm/s. - The vertical speed. Up is positive. If unknown: 6300 cm/s. If speed is larger than 6200 cm/s, use 6200 cm/s. If lower than -6200 cm/s, use -6200 cm/s. - Current latitude of the unmanned aircraft. If unknown: 0 (both Lat/Lon). - Current longitude of the unmanned aircraft. If unknown: 0 (both Lat/Lon). - The altitude calculated from the barometric pressue. Reference is against 29.92inHg or 1013.2mb. If unknown: -1000 m. - The geodetic altitude as defined by WGS84. If unknown: -1000 m. - Indicates the reference point for the height field. - The current height of the unmanned aircraft above the take-off location or the ground as indicated by height_reference. If unknown: -1000 m. - The accuracy of the horizontal position. - The accuracy of the vertical position. - The accuracy of the barometric altitude. - The accuracy of the horizontal and vertical speed. - Seconds after the full hour with reference to UTC time. Typically the GPS outputs a time-of-week value in milliseconds. First convert that to UTC and then convert for this field using ((float) (time_week_ms % (60*60*1000))) / 1000. If unknown: 0xFFFF. - The accuracy of the timestamps. - - - Data for filling the OpenDroneID Authentication message. The Authentication Message defines a field that can provide a means of authenticity for the identity of the UAS (Unmanned Aircraft System). The Authentication message can have two different formats. For data page 0, the fields PageCount, Length and TimeStamp are present and AuthData is only 17 bytes. For data page 1 through 15, PageCount, Length and TimeStamp are not present and the size of AuthData is 23 bytes. - System ID (0 for broadcast). - Component ID (0 for broadcast). - Only used for drone ID data received from other UAs. See detailed description at https://mavlink.io/en/services/opendroneid.html. - Indicates the type of authentication. - Allowed range is 0 - 15. - This field is only present for page 0. Allowed range is 0 - 15. See the description of struct ODID_Auth_data at https://github.com/opendroneid/opendroneid-core-c/blob/master/libopendroneid/opendroneid.h. - This field is only present for page 0. Total bytes of authentication_data from all data pages. See the description of struct ODID_Auth_data at https://github.com/opendroneid/opendroneid-core-c/blob/master/libopendroneid/opendroneid.h. - This field is only present for page 0. 32 bit Unix Timestamp in seconds since 00:00:00 01/01/2019. - Opaque authentication data. For page 0, the size is only 17 bytes. For other pages, the size is 23 bytes. Shall be filled with nulls in the unused portion of the field. - - - Data for filling the OpenDroneID Self ID message. The Self ID Message is an opportunity for the operator to (optionally) declare their identity and purpose of the flight. This message can provide additional information that could reduce the threat profile of a UA (Unmanned Aircraft) flying in a particular area or manner. This message can also be used to provide optional additional clarification in an emergency/remote ID system failure situation. - System ID (0 for broadcast). - Component ID (0 for broadcast). - Only used for drone ID data received from other UAs. See detailed description at https://mavlink.io/en/services/opendroneid.html. - Indicates the type of the description field. - Text description or numeric value expressed as ASCII characters. Shall be filled with nulls in the unused portion of the field. - - - Data for filling the OpenDroneID System message. The System Message contains general system information including the operator location/altitude and possible aircraft group and/or category/class information. - System ID (0 for broadcast). - Component ID (0 for broadcast). - Only used for drone ID data received from other UAs. See detailed description at https://mavlink.io/en/services/opendroneid.html. - Specifies the operator location type. - Specifies the classification type of the UA. - Latitude of the operator. If unknown: 0 (both Lat/Lon). - Longitude of the operator. If unknown: 0 (both Lat/Lon). - Number of aircraft in the area, group or formation (default 1). Used only for swarms/multiple UA. - Radius of the cylindrical area of the group or formation (default 0). Used only for swarms/multiple UA. - Area Operations Ceiling relative to WGS84. If unknown: -1000 m. Used only for swarms/multiple UA. - Area Operations Floor relative to WGS84. If unknown: -1000 m. Used only for swarms/multiple UA. - When classification_type is MAV_ODID_CLASSIFICATION_TYPE_EU, specifies the category of the UA. - When classification_type is MAV_ODID_CLASSIFICATION_TYPE_EU, specifies the class of the UA. - Geodetic altitude of the operator relative to WGS84. If unknown: -1000 m. - 32 bit Unix Timestamp in seconds since 00:00:00 01/01/2019. - - - Data for filling the OpenDroneID Operator ID message, which contains the CAA (Civil Aviation Authority) issued operator ID. - System ID (0 for broadcast). - Component ID (0 for broadcast). - Only used for drone ID data received from other UAs. See detailed description at https://mavlink.io/en/services/opendroneid.html. - Indicates the type of the operator_id field. - Text description or numeric value expressed as ASCII characters. Shall be filled with nulls in the unused portion of the field. - - - - An OpenDroneID message pack is a container for multiple encoded OpenDroneID messages (i.e. not in the format given for the above message descriptions but after encoding into the compressed OpenDroneID byte format). Used e.g. when transmitting on Bluetooth 5.0 Long Range/Extended Advertising or on WiFi Neighbor Aware Networking or on WiFi Beacon. - System ID (0 for broadcast). - Component ID (0 for broadcast). - Only used for drone ID data received from other UAs. See detailed description at https://mavlink.io/en/services/opendroneid.html. - This field must currently always be equal to 25 (bytes), since all encoded OpenDroneID messages are specified to have this length. - Number of encoded messages in the pack (not the number of bytes). Allowed range is 1 - 9. - Concatenation of encoded OpenDroneID messages. Shall be filled with nulls in the unused portion of the field. - - - - Transmitter (remote ID system) is enabled and ready to start sending location and other required information. This is streamed by transmitter. A flight controller uses it as a condition to arm. - Status level indicating if arming is allowed. - Text error message, should be empty if status is good to arm. Fill with nulls in unused portion. - - - Update the data in the OPEN_DRONE_ID_SYSTEM message with new location information. This can be sent to update the location information for the operator when no other information in the SYSTEM message has changed. This message allows for efficient operation on radio links which have limited uplink bandwidth while meeting requirements for update frequency of the operator location. - System ID (0 for broadcast). - Component ID (0 for broadcast). - Latitude of the operator. If unknown: 0 (both Lat/Lon). - Longitude of the operator. If unknown: 0 (both Lat/Lon). - Geodetic altitude of the operator relative to WGS84. If unknown: -1000 m. - 32 bit Unix Timestamp in seconds since 00:00:00 01/01/2019. - - - Temperature and humidity from hygrometer. - Hygrometer ID - Temperature - Humidity - - - diff --git a/TelemetryManager/Inc/official_mavlink_2_library/message_definitions/csAirLink.xml b/TelemetryManager/Inc/official_mavlink_2_library/message_definitions/csAirLink.xml deleted file mode 100644 index 2f6c7da7..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/message_definitions/csAirLink.xml +++ /dev/null @@ -1,29 +0,0 @@ - - - - - - - 3 - - - - Login or password error - - - Auth successful - - - - - - Authorization package - Login - Password - - - Response to the authorization request - Response type - - - diff --git a/TelemetryManager/Inc/official_mavlink_2_library/message_definitions/cubepilot.xml b/TelemetryManager/Inc/official_mavlink_2_library/message_definitions/cubepilot.xml deleted file mode 100644 index 65b58c8c..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/message_definitions/cubepilot.xml +++ /dev/null @@ -1,48 +0,0 @@ - - - - - - - common.xml - - - Raw RC Data - - - - Information about video stream - Video Stream ID (1 for first, 2 for second, etc.) - Number of streams available. - Frame rate. - Horizontal resolution. - Vertical resolution. - Bit rate. - Video image rotation clockwise. - Video stream URI (TCP or RTSP URI ground station should connect to) or port number (UDP port ground station should listen to). - - - Herelink Telemetry - - - - - - - - - - Start firmware update with encapsulated data. - System ID. - Component ID. - FW Size. - FW CRC. - - - offset response to encapsulated data. - System ID. - Component ID. - FW Offset. - - - diff --git a/TelemetryManager/Inc/official_mavlink_2_library/message_definitions/development.xml b/TelemetryManager/Inc/official_mavlink_2_library/message_definitions/development.xml deleted file mode 100644 index 9e0057a2..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/message_definitions/development.xml +++ /dev/null @@ -1,551 +0,0 @@ - - - - common.xml - 0 - 0 - - - WiFi wireless security protocols. - - Undefined or unknown security protocol. - - - Open network, no security. - - - WEP. - - - WPA1. - - - WPA2. - - - WPA3. - - - - Airspeed sensor flags - - Airspeed sensor is unhealthy - - - True if the data from this sensor is being actively used by the flight controller for guidance, navigation or control. - - - - - Possible transport layers to set and get parameters via mavlink during a parameter transaction. - - Transaction over param transport. - - - Transaction over param_ext transport. - - - - Possible parameter transaction actions. - - Commit the current parameter transaction. - - - Commit the current parameter transaction. - - - Cancel the current parameter transaction. - - - - Standard modes with a well understood meaning across flight stacks and vehicle types. - For example, most flight stack have the concept of a "return" or "RTL" mode that takes a vehicle to safety, even though the precise mechanics of this mode may differ. - Modes may be set using MAV_CMD_DO_SET_STANDARD_MODE. - - - Non standard mode. - This may be used when reporting the mode if the current flight mode is not a standard mode. - - - - Position mode (manual). - Position-controlled and stabilized manual mode. - When sticks are released vehicles return to their level-flight orientation and hold both position and altitude against wind and external forces. - This mode can only be set by vehicles that can hold a fixed position. - Multicopter (MC) vehicles actively brake and hold both position and altitude against wind and external forces. - Hybrid MC/FW ("VTOL") vehicles first transition to multicopter mode (if needed) but otherwise behave in the same way as MC vehicles. - Fixed-wing (FW) vehicles must not support this mode. - Other vehicle types must not support this mode (this may be revisited through the PR process). - - - - Orbit (manual). - Position-controlled and stabilized manual mode. - The vehicle circles around a fixed setpoint in the horizontal plane at a particular radius, altitude, and direction. - Flight stacks may further allow manual control over the setpoint position, radius, direction, speed, and/or altitude of the circle, but this is not mandated. - Flight stacks may support the [MAV_CMD_DO_ORBIT](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_ORBIT) for changing the orbit parameters. - MC and FW vehicles may support this mode. - Hybrid MC/FW ("VTOL") vehicles may support this mode in MC/FW or both modes; if the mode is not supported by the current configuration the vehicle should transition to the supported configuration. - Other vehicle types must not support this mode (this may be revisited through the PR process). - - - - Cruise mode (manual). - Position-controlled and stabilized manual mode. - When sticks are released vehicles return to their level-flight orientation and hold their original track against wind and external forces. - Fixed-wing (FW) vehicles level orientation and maintain current track and altitude against wind and external forces. - Hybrid MC/FW ("VTOL") vehicles first transition to FW mode (if needed) but otherwise behave in the same way as MC vehicles. - Multicopter (MC) vehicles must not support this mode. - Other vehicle types must not support this mode (this may be revisited through the PR process). - - - - Altitude hold (manual). - Altitude-controlled and stabilized manual mode. - When sticks are released vehicles return to their level-flight orientation and hold their altitude. - MC vehicles continue with existing momentum and may move with wind (or other external forces). - FW vehicles continue with current heading, but may be moved off-track by wind. - Hybrid MC/FW ("VTOL") vehicles behave according to their current configuration/mode (FW or MC). - Other vehicle types must not support this mode (this may be revisited through the PR process). - - - - Return home mode (auto). - Automatic mode that returns vehicle to home via a safe flight path. - It may also automatically land the vehicle (i.e. RTL). - The precise flight path and landing behaviour depend on vehicle configuration and type. - - - - Safe recovery mode (auto). - Automatic mode that takes vehicle to a predefined safe location via a safe flight path (rally point or mission defined landing) . - It may also automatically land the vehicle. - The precise return location, flight path, and landing behaviour depend on vehicle configuration and type. - - - - Mission mode (automatic). - Automatic mode that executes MAVLink missions. - Missions are executed from the current waypoint as soon as the mode is enabled. - - - - Land mode (auto). - Automatic mode that lands the vehicle at the current location. - The precise landing behaviour depends on vehicle configuration and type. - - - - Takeoff mode (auto). - Automatic takeoff mode. - The precise takeoff behaviour depends on vehicle configuration and type. - - - - - Mode properties. - - - If set, this mode is an advanced mode. - For example a rate-controlled manual mode might be advanced, whereas a position-controlled manual mode is not. - A GCS can optionally use this flag to configure the UI for its intended users. - - - - If set, this mode should not be added to the list of selectable modes. - The mode might still be selected by the FC directly (for example as part of a failsafe). - - - - - - - - - Commands to be executed by the MAV. They can be executed on user request, or as part of a mission script. If the action is used in a mission, the parameter mapping to the waypoint/mission message is as follows: Param 1, Param 2, Param 3, Param 4, X: Param 5, Y:Param 6, Z:Param 7. This command list is similar what ARINC 424 is for commercial aircraft: A data format how to interpret waypoint/mission data. NaN and INT32_MAX may be used in float/integer params (respectively) to indicate optional/default values (e.g. to use the component's current yaw or latitude rather than a specific value). See https://mavlink.io/en/guide/xml_schema.html#MAV_CMD for information about the structure of the MAV_CMD entries - - - - Fly a figure eight path as defined by the parameters. - Set parameters to NaN/INT32_MAX (as appropriate) to use system-default values. - The command is intended for fixed wing vehicles (and VTOL hybrids flying in fixed-wing mode), allowing POI tracking for gimbals that don't support infinite rotation. - This command only defines the flight path. Speed should be set independently (use e.g. MAV_CMD_DO_CHANGE_SPEED). - Yaw and other degrees of freedom are not specified, and will be flight-stack specific (on vehicles where they can be controlled independent of the heading). - - Major axis radius of the figure eight. Positive: orbit the north circle clockwise. Negative: orbit the north circle counter-clockwise. - NaN: The radius will be set to 2.5 times the minor radius and direction is clockwise. - Must be greater or equal to two times the minor radius for feasible values. - Minor axis radius of the figure eight. Defines the radius of the two circles that make up the figure. Negative value has no effect. - NaN: The radius will be set to the default loiter radius. - - Orientation of the figure eight major axis with respect to true north (range: [-pi,pi]). NaN: use default orientation aligned to true north. - Center point latitude/X coordinate according to MAV_FRAME. If no MAV_FRAME specified, MAV_FRAME_GLOBAL is assumed. - INT32_MAX or NaN: Use current vehicle position, or current center if already loitering. - Center point longitude/Y coordinate according to MAV_FRAME. If no MAV_FRAME specified, MAV_FRAME_GLOBAL is assumed. - INT32_MAX or NaN: Use current vehicle position, or current center if already loitering. - Center point altitude MSL/Z coordinate according to MAV_FRAME. If no MAV_FRAME specified, MAV_FRAME_GLOBAL is assumed. - INT32_MAX or NaN: Use current vehicle altitude. - - - Request to start or end a parameter transaction. Multiple kinds of transport layers can be used to exchange parameters in the transaction (param, param_ext and mavftp). The command response can either be a success/failure or an in progress in case the receiving side takes some time to apply the parameters. - Action to be performed (start, commit, cancel, etc.) - Possible transport layers to set and get parameters via mavlink during a parameter transaction. - Identifier for a specific transaction. - - - Sets the action on geofence breach. - If sent using the command protocol this sets the system-default geofence action. - As part of a mission protocol plan it sets the fence action for the next complete geofence definition *after* the command. - Note: A fence action defined in a plan will override the default system setting (even if the system-default is `FENCE_ACTION_NONE`). - Note: Every geofence in a plan can have its own action; if no fence action is defined for a particular fence the system-default will be used. - Note: The flight stack should reject a plan or command that uses a geofence action that it does not support and send a STATUSTEXT with the reason. - - Fence action on breach. - - - - Battery status flags for fault, health and state indication. - - - The battery is not ready to use (fly). - Set if the battery has faults or other conditions that make it unsafe to fly with. - Note: It will be the logical OR of other status bits (chosen by the manufacturer/integrator). - - - - - Battery is charging. - - - - - Battery is cell balancing (during charging). - Not ready to use (MAV_BATTERY_STATUS_FLAGS_NOT_READY_TO_USE may be set). - - - - - Battery cells are not balanced. - Not ready to use. - - - - - Battery is auto discharging (towards storage level). - Not ready to use (MAV_BATTERY_STATUS_FLAGS_NOT_READY_TO_USE would be set). - - - - - Battery requires service (not safe to fly). - This is set at vendor discretion. - It is likely to be set for most faults, and may also be set according to a maintenance schedule (such as age, or number of recharge cycles, etc.). - - - - - Battery is faulty and cannot be repaired (not safe to fly). - This is set at vendor discretion. - The battery should be disposed of safely. - - - - - Automatic battery protection monitoring is enabled. - When enabled, the system will monitor for certain kinds of faults, such as cells being over-voltage. - If a fault is triggered then and protections are enabled then a safety fault (MAV_BATTERY_STATUS_FLAGS_FAULT_PROTECTION_SYSTEM) will be set and power from the battery will be stopped. - Note that battery protection monitoring should only be enabled when the vehicle is landed. Once the vehicle is armed, or starts moving, the protections should be disabled to prevent false positives from disabling the output. - - - - - The battery fault protection system had detected a fault and cut all power from the battery. - This will only trigger if MAV_BATTERY_STATUS_FLAGS_PROTECTIONS_ENABLED is set. - Other faults like MAV_BATTERY_STATUS_FLAGS_FAULT_OVER_VOLT may also be set, indicating the cause of the protection fault. - - - - One or more cells are above their maximum voltage rating. - - - - One or more cells are below their minimum voltage rating. - A battery that had deep-discharged might be irrepairably damaged, and set both MAV_BATTERY_STATUS_FLAGS_FAULT_UNDER_VOLT and MAV_BATTERY_STATUS_FLAGS_BAD_BATTERY. - - - - Over-temperature fault. - - - Under-temperature fault. - - - Over-current fault. - - - - Short circuit event detected. - The battery may or may not be safe to use (check other flags). - - - - Voltage not compatible with power rail voltage (batteries on same power rail should have similar voltage). - - - Battery firmware is not compatible with current autopilot firmware. - - - Battery is not compatible due to cell configuration (e.g. 5s1p when vehicle requires 6s). - - - - Battery capacity_consumed and capacity_remaining values are relative to a full battery (they sum to the total capacity of the battery). - This flag would be set for a smart battery that can accurately determine its remaining charge across vehicle reboots and discharge/recharge cycles. - If unset the capacity_consumed indicates the consumption since vehicle power-on, as measured using a power monitor. The capacity_remaining, if provided, indicates the estimated remaining capacity on the assumption that the battery was full on vehicle boot. - If unset a GCS is recommended to advise that users fully charge the battery on power on. - - - - Reserved (not used). If set, this will indicate that an additional status field exists for higher status values. - - - - - Request a target system to start an upgrade of one (or all) of its components. - For example, the command might be sent to a companion computer to cause it to upgrade a connected flight controller. - The system doing the upgrade will report progress using the normal command protocol sequence for a long running operation. - Command protocol information: https://mavlink.io/en/services/command.html. - Component id of the component to be upgraded. If set to 0, all components should be upgraded. - 0: Do not reboot component after the action is executed, 1: Reboot component after the action is executed. - Reserved - Reserved - Reserved - Reserved - WIP: upgrade progress report rate (can be used for more granular control). - - - Define start of a group of mission items. When control reaches this command a GROUP_START message is emitted. - The end of a group is marked using MAV_CMD_GROUP_END with the same group id. - Group ids are expected, but not required, to iterate sequentially. - Groups can be nested. - Mission-unique group id. - Group id is limited because only 24 bit integer can be stored in 32 bit float. - - - Define end of a group of mission items. When control reaches this command a GROUP_END message is emitted. - The start of the group is marked is marked using MAV_CMD_GROUP_START with the same group id. - Group ids are expected, but not required, to iterate sequentially. - Groups can be nested. - Mission-unique group id. - Group id is limited because only 24 bit integer can be stored in 32 bit float. - - - Enable the specified standard MAVLink mode. - If the mode is not supported the vehicle should ACK with MAV_RESULT_FAILED. - - The mode to set. - - - - - - - - - Allows setting an AT S command of an SiK radio. - - The radio instance, one-based, 0 for all. - The Sx index, e.g. 3 for S3 which is NETID. - The value to set it to, e.g. default 25 for NETID - - - - - - - - These flags indicate the sensor reporting capabilities for TARGET_ABSOLUTE. - - - - - - - - The frame of a target observation from an onboard sensor. - - NED local tangent frame (x: North, y: East, z: Down) with origin fixed relative to earth. - - - FRD local frame aligned to the vehicle's attitude (x: Forward, y: Right, z: Down) with an origin that travels with vehicle. - - - NED local tangent frame (x: North, y: East, z: Down) with an origin that travels with vehicle. - - - Other sensor frame for target observations neither in local NED nor in body FRD. - - - - - - - Response from a PARAM_SET message when it is used in a transaction. - Id of system that sent PARAM_SET message. - Id of system that sent PARAM_SET message. - Parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string - Parameter value (new value if PARAM_ACCEPTED, current value otherwise) - Parameter type. - Result code. - - - - Checksum for the current mission, rally point or geofence plan, or for the "combined" plan (a GCS can use these checksums to determine if it has matching plans). - This message must be broadcast with the appropriate checksum following any change to a mission, geofence or rally point definition - (immediately after the MISSION_ACK that completes the upload sequence). - It may also be requested using MAV_CMD_REQUEST_MESSAGE, where param 2 indicates the plan type for which the checksum is required. - The checksum must be calculated on the autopilot, but may also be calculated by the GCS. - The checksum uses the same CRC32 algorithm as MAVLink FTP (https://mavlink.io/en/services/ftp.html#crc32-implementation). - The checksum for a mission, geofence or rally point definition is run over each item in the plan in seq order (excluding the home location if present in the plan), and covers the following fields (in order): - frame, command, autocontinue, param1, param2, param3, param4, param5, param6, param7. - The checksum for the whole plan (MAV_MISSION_TYPE_ALL) is calculated using the same approach, running over each sub-plan in the following order: mission, geofence then rally point. - - Mission type. - CRC32 checksum of current plan for specified type. - - - Airspeed information from a sensor. - Sensor ID. - Calibrated airspeed (CAS). - Temperature. INT16_MAX for value unknown/not supplied. - Raw differential pressure. NaN for value unknown/not supplied. - Airspeed sensor flags. - - - Detected WiFi network status information. This message is sent per each WiFi network detected in range with known SSID and general status parameters. - Name of Wi-Fi network (SSID). - WiFi network operating channel ID. Set to 0 if unknown or unidentified. - WiFi network signal quality. - WiFi network data rate. Set to UINT16_MAX if data_rate information is not supplied. - WiFi network security type. - - - - - - Vehicle status report that is sent out while figure eight execution is in progress (see MAV_CMD_DO_FIGURE_EIGHT). - This may typically send at low rates: of the order of 2Hz. - - Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - Major axis radius of the figure eight. Positive: orbit the north circle clockwise. Negative: orbit the north circle counter-clockwise. - Minor axis radius of the figure eight. Defines the radius of two circles that make up the figure. - Orientation of the figure eight major axis with respect to true north in [-pi,pi). - The coordinate system of the fields: x, y, z. - X coordinate of center point. Coordinate system depends on frame field. - Y coordinate of center point. Coordinate system depends on frame field. - Altitude of center point. Coordinate system depends on frame field. - - - Battery dynamic information. - This should be streamed (nominally at 1Hz). - Static/invariant battery information is sent in SMART_BATTERY_INFO. - Note that smart batteries should set the MAV_BATTERY_STATUS_FLAGS_CAPACITY_RELATIVE_TO_FULL bit to indicate that supplied capacity values are relative to a battery that is known to be full. - Power monitors would not set this bit, indicating that capacity_consumed is relative to drone power-on, and that other values are estimated based on the assumption that the battery was full on power-on. - - Battery ID - Temperature of the whole battery pack (not internal electronics). INT16_MAX field not provided. - Battery voltage (total). NaN: field not provided. - Battery current (through all cells/loads). Positive value when discharging and negative if charging. NaN: field not provided. - Consumed charge. NaN: field not provided. This is either the consumption since power-on or since the battery was full, depending on the value of MAV_BATTERY_STATUS_FLAGS_CAPACITY_RELATIVE_TO_FULL. - Remaining charge (until empty). UINT32_MAX: field not provided. Note: If MAV_BATTERY_STATUS_FLAGS_CAPACITY_RELATIVE_TO_FULL is unset, this value is based on the assumption the battery was full when the system was powered. - Remaining battery energy. Values: [0-100], UINT8_MAX: field not provided. - Fault, health, readiness, and other status indications. - - - Basic component information data. Should be requested using MAV_CMD_REQUEST_MESSAGE on startup, or when required. - Timestamp (time since system boot). - Component capability flags - Name of the component vendor. Needs to be zero terminated. The field is optional and can be empty/all zeros. - Name of the component model. Needs to be zero terminated. The field is optional and can be empty/all zeros. - Software version. The recommended format is SEMVER: 'major.minor.patch' (any format may be used). The field must be zero terminated if it has a value. The field is optional and can be empty/all zeros. - Hardware version. The recommended format is SEMVER: 'major.minor.patch' (any format may be used). The field must be zero terminated if it has a value. The field is optional and can be empty/all zeros. - Hardware serial number. The field must be zero terminated if it has a value. The field is optional and can be empty/all zeros. - - - Emitted during mission execution when control reaches MAV_CMD_GROUP_START. - Mission-unique group id (from MAV_CMD_GROUP_START). - CRC32 checksum of current plan for MAV_MISSION_TYPE_ALL. As defined in MISSION_CHECKSUM message. - Timestamp (UNIX Epoch time or time since system boot). - The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - - - Emitted during mission execution when control reaches MAV_CMD_GROUP_END. - Mission-unique group id (from MAV_CMD_GROUP_END). - CRC32 checksum of current plan for MAV_MISSION_TYPE_ALL. As defined in MISSION_CHECKSUM message. - Timestamp (UNIX Epoch time or time since system boot). - The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. - - - Get information about a particular flight modes. - The message can be enumerated or requested for a particular mode using MAV_CMD_REQUEST_MESSAGE. - Specify 0 in param2 to request that the message is emitted for all available modes or the specific index for just one mode. - The modes must be available/settable for the current vehicle/frame type. - Each modes should only be emitted once (even if it is both standard and custom). - - The total number of available modes for the current vehicle type. - The current mode index within number_modes, indexed from 1. - Standard mode. - A bitfield for use for autopilot-specific flags - Mode properties. - Name of custom mode, with null termination character. Should be omitted for standard modes. - - - Get the current mode. - This should be emitted on any mode change, and broadcast at low rate (nominally 0.5 Hz). - It may be requested using MAV_CMD_REQUEST_MESSAGE. - - Standard mode. - A bitfield for use for autopilot-specific flags - The custom_mode of the mode that was last commanded by the user (for example, with MAV_CMD_DO_SET_STANDARD_MODE, MAV_CMD_DO_SET_MODE or via RC). This should usually be the same as custom_mode. It will be different if the vehicle is unable to enter the intended mode, or has left that mode due to a failsafe condition. 0 indicates the intended custom mode is unknown/not supplied - - - A change to the sequence number indicates that the set of AVAILABLE_MODES has changed. - A receiver must re-request all available modes whenever the sequence number changes. - This is only emitted after the first change and should then be broadcast at low rate (nominally 0.3 Hz) and on change. - - Sequence number. The value iterates sequentially whenever AVAILABLE_MODES changes (e.g. support for a new mode is added/removed dynamically). - - - - Current motion information from sensors on a target - Timestamp (UNIX epoch time). - The ID of the target if multiple targets are present - Bitmap to indicate the sensor's reporting capabilities - Target's latitude (WGS84) - Target's longitude (WGS84) - Target's altitude (AMSL) - Target's velocity in its body frame - Linear target's acceleration in its body frame - Quaternion of the target's orientation from its body frame to the vehicle's NED frame. - Target's roll, pitch and yaw rates - Standard deviation of horizontal (eph) and vertical (epv) position errors - Standard deviation of the target's velocity in its body frame - Standard deviation of the target's acceleration in its body frame - - - - The location of a target measured by MAV's onboard sensors. - Timestamp (UNIX epoch time) - The ID of the target if multiple targets are present - Coordinate frame used for following fields. - X Position of the target in TARGET_OBS_FRAME - Y Position of the target in TARGET_OBS_FRAME - Z Position of the target in TARGET_OBS_FRAME - Standard deviation of the target's position in TARGET_OBS_FRAME - Standard deviation of the target's orientation in TARGET_OBS_FRAME - Quaternion of the target's orientation from the target's frame to the TARGET_OBS_FRAME (w, x, y, z order, zero-rotation is 1, 0, 0, 0) - Quaternion of the sensor's orientation from TARGET_OBS_FRAME to vehicle-carried NED. (Ignored if set to (0,0,0,0)) (w, x, y, z order, zero-rotation is 1, 0, 0, 0) - Type of target - - - diff --git a/TelemetryManager/Inc/official_mavlink_2_library/message_definitions/icarous.xml b/TelemetryManager/Inc/official_mavlink_2_library/message_definitions/icarous.xml deleted file mode 100644 index 7dbdb95e..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/message_definitions/icarous.xml +++ /dev/null @@ -1,48 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - ICAROUS heartbeat - See the FMS_STATE enum. - - - Kinematic multi bands (track) output from Daidalus - Number of track bands - See the TRACK_BAND_TYPES enum. - min angle (degrees) - max angle (degrees) - See the TRACK_BAND_TYPES enum. - min angle (degrees) - max angle (degrees) - See the TRACK_BAND_TYPES enum. - min angle (degrees) - max angle (degrees) - See the TRACK_BAND_TYPES enum. - min angle (degrees) - max angle (degrees) - See the TRACK_BAND_TYPES enum. - min angle (degrees) - max angle (degrees) - - - diff --git a/TelemetryManager/Inc/official_mavlink_2_library/message_definitions/matrixpilot.xml b/TelemetryManager/Inc/official_mavlink_2_library/message_definitions/matrixpilot.xml deleted file mode 100644 index 3ca9aa72..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/message_definitions/matrixpilot.xml +++ /dev/null @@ -1,349 +0,0 @@ - - - common.xml - - - - Action required when performing CMD_PREFLIGHT_STORAGE - - Read all parameters from storage - - - Write all parameters to storage - - - Clear all parameters in storage - - - Read specific parameters from storage - - - Write specific parameters to storage - - - Clear specific parameters in storage - - - do nothing - - - - - Request storage of different parameter values and logs. This command will be only accepted if in pre-flight mode. - Storage action: Action defined by MAV_PREFLIGHT_STORAGE_ACTION_ADVANCED - Storage area as defined by parameter database - Storage flags as defined by parameter database - Empty - Empty - Empty - Empty - - - - - - Depreciated but used as a compiler flag. Do not remove - System ID - Component ID - - - Request reading of flexifunction data - System ID - Component ID - Type of flexifunction data requested - index into data where needed - - - Flexifunction type and parameters for component at function index from buffer - System ID - Component ID - Function index - Total count of functions - Address in the flexifunction data, Set to 0xFFFF to use address in target memory - Size of the - Settings data - - - Flexifunction type and parameters for component at function index from buffer - System ID - Component ID - Function index - result of acknowledge, 0=fail, 1=good - - - Acknowldge success or failure of a flexifunction command - System ID - Component ID - 0=inputs, 1=outputs - index of first directory entry to write - count of directory entries to write - Settings data - - - Acknowldge success or failure of a flexifunction command - System ID - Component ID - 0=inputs, 1=outputs - index of first directory entry to write - count of directory entries to write - result of acknowledge, 0=fail, 1=good - - - Acknowldge success or failure of a flexifunction command - System ID - Component ID - Flexifunction command type - - - Acknowldge success or failure of a flexifunction command - Command acknowledged - result of acknowledge - - - Backwards compatible MAVLink version of SERIAL_UDB_EXTRA - F2: Format Part A - Serial UDB Extra Time - Serial UDB Extra Status - Serial UDB Extra Latitude - Serial UDB Extra Longitude - Serial UDB Extra Altitude - Serial UDB Extra Waypoint Index - Serial UDB Extra Rmat 0 - Serial UDB Extra Rmat 1 - Serial UDB Extra Rmat 2 - Serial UDB Extra Rmat 3 - Serial UDB Extra Rmat 4 - Serial UDB Extra Rmat 5 - Serial UDB Extra Rmat 6 - Serial UDB Extra Rmat 7 - Serial UDB Extra Rmat 8 - Serial UDB Extra GPS Course Over Ground - Serial UDB Extra Speed Over Ground - Serial UDB Extra CPU Load - Serial UDB Extra 3D IMU Air Speed - Serial UDB Extra Estimated Wind 0 - Serial UDB Extra Estimated Wind 1 - Serial UDB Extra Estimated Wind 2 - Serial UDB Extra Magnetic Field Earth 0 - Serial UDB Extra Magnetic Field Earth 1 - Serial UDB Extra Magnetic Field Earth 2 - Serial UDB Extra Number of Satellites in View - Serial UDB Extra GPS Horizontal Dilution of Precision - - - Backwards compatible version of SERIAL_UDB_EXTRA - F2: Part B - Serial UDB Extra Time - Serial UDB Extra PWM Input Channel 1 - Serial UDB Extra PWM Input Channel 2 - Serial UDB Extra PWM Input Channel 3 - Serial UDB Extra PWM Input Channel 4 - Serial UDB Extra PWM Input Channel 5 - Serial UDB Extra PWM Input Channel 6 - Serial UDB Extra PWM Input Channel 7 - Serial UDB Extra PWM Input Channel 8 - Serial UDB Extra PWM Input Channel 9 - Serial UDB Extra PWM Input Channel 10 - Serial UDB Extra PWM Input Channel 11 - Serial UDB Extra PWM Input Channel 12 - Serial UDB Extra PWM Output Channel 1 - Serial UDB Extra PWM Output Channel 2 - Serial UDB Extra PWM Output Channel 3 - Serial UDB Extra PWM Output Channel 4 - Serial UDB Extra PWM Output Channel 5 - Serial UDB Extra PWM Output Channel 6 - Serial UDB Extra PWM Output Channel 7 - Serial UDB Extra PWM Output Channel 8 - Serial UDB Extra PWM Output Channel 9 - Serial UDB Extra PWM Output Channel 10 - Serial UDB Extra PWM Output Channel 11 - Serial UDB Extra PWM Output Channel 12 - Serial UDB Extra IMU Location X - Serial UDB Extra IMU Location Y - Serial UDB Extra IMU Location Z - Serial UDB Location Error Earth X - Serial UDB Location Error Earth Y - Serial UDB Location Error Earth Z - Serial UDB Extra Status Flags - Serial UDB Extra Oscillator Failure Count - Serial UDB Extra IMU Velocity X - Serial UDB Extra IMU Velocity Y - Serial UDB Extra IMU Velocity Z - Serial UDB Extra Current Waypoint Goal X - Serial UDB Extra Current Waypoint Goal Y - Serial UDB Extra Current Waypoint Goal Z - Aeroforce in UDB X Axis - Aeroforce in UDB Y Axis - Aeroforce in UDB Z axis - SUE barometer temperature - SUE barometer pressure - SUE barometer altitude - SUE battery voltage - SUE battery current - SUE battery milli amp hours used - Sue autopilot desired height - Serial UDB Extra Stack Memory Free - - - Backwards compatible version of SERIAL_UDB_EXTRA F4: format - Serial UDB Extra Roll Stabilization with Ailerons Enabled - Serial UDB Extra Roll Stabilization with Rudder Enabled - Serial UDB Extra Pitch Stabilization Enabled - Serial UDB Extra Yaw Stabilization using Rudder Enabled - Serial UDB Extra Yaw Stabilization using Ailerons Enabled - Serial UDB Extra Navigation with Ailerons Enabled - Serial UDB Extra Navigation with Rudder Enabled - Serial UDB Extra Type of Alitude Hold when in Stabilized Mode - Serial UDB Extra Type of Alitude Hold when in Waypoint Mode - Serial UDB Extra Firmware racing mode enabled - - - Backwards compatible version of SERIAL_UDB_EXTRA F5: format - Serial UDB YAWKP_AILERON Gain for Proporional control of navigation - Serial UDB YAWKD_AILERON Gain for Rate control of navigation - Serial UDB Extra ROLLKP Gain for Proportional control of roll stabilization - Serial UDB Extra ROLLKD Gain for Rate control of roll stabilization - - - Backwards compatible version of SERIAL_UDB_EXTRA F6: format - Serial UDB Extra PITCHGAIN Proportional Control - Serial UDB Extra Pitch Rate Control - Serial UDB Extra Rudder to Elevator Mix - Serial UDB Extra Roll to Elevator Mix - Gain For Boosting Manual Elevator control When Plane Stabilized - - - Backwards compatible version of SERIAL_UDB_EXTRA F7: format - Serial UDB YAWKP_RUDDER Gain for Proporional control of navigation - Serial UDB YAWKD_RUDDER Gain for Rate control of navigation - Serial UDB Extra ROLLKP_RUDDER Gain for Proportional control of roll stabilization - Serial UDB Extra ROLLKD_RUDDER Gain for Rate control of roll stabilization - SERIAL UDB EXTRA Rudder Boost Gain to Manual Control when stabilized - Serial UDB Extra Return To Landing - Angle to Pitch Plane Down - - - Backwards compatible version of SERIAL_UDB_EXTRA F8: format - Serial UDB Extra HEIGHT_TARGET_MAX - Serial UDB Extra HEIGHT_TARGET_MIN - Serial UDB Extra ALT_HOLD_THROTTLE_MIN - Serial UDB Extra ALT_HOLD_THROTTLE_MAX - Serial UDB Extra ALT_HOLD_PITCH_MIN - Serial UDB Extra ALT_HOLD_PITCH_MAX - Serial UDB Extra ALT_HOLD_PITCH_HIGH - - - Backwards compatible version of SERIAL_UDB_EXTRA F13: format - Serial UDB Extra GPS Week Number - Serial UDB Extra MP Origin Latitude - Serial UDB Extra MP Origin Longitude - Serial UDB Extra MP Origin Altitude Above Sea Level - - - Backwards compatible version of SERIAL_UDB_EXTRA F14: format - Serial UDB Extra Wind Estimation Enabled - Serial UDB Extra Type of GPS Unit - Serial UDB Extra Dead Reckoning Enabled - Serial UDB Extra Type of UDB Hardware - Serial UDB Extra Type of Airframe - Serial UDB Extra Reboot Register of DSPIC - Serial UDB Extra Last dspic Trap Flags - Serial UDB Extra Type Program Address of Last Trap - Serial UDB Extra Number of Ocillator Failures - Serial UDB Extra UDB Internal Clock Configuration - Serial UDB Extra Type of Flight Plan - - - Backwards compatible version of SERIAL_UDB_EXTRA F15 format - Serial UDB Extra Model Name Of Vehicle - Serial UDB Extra Registraton Number of Vehicle - - - Backwards compatible version of SERIAL_UDB_EXTRA F16 format - Serial UDB Extra Name of Expected Lead Pilot - Serial UDB Extra URL of Lead Pilot or Team - - - The altitude measured by sensors and IMU - Timestamp (milliseconds since system boot) - GPS altitude (MSL) in meters, expressed as * 1000 (millimeters) - IMU altitude above ground in meters, expressed as * 1000 (millimeters) - barometeric altitude above ground in meters, expressed as * 1000 (millimeters) - Optical flow altitude above ground in meters, expressed as * 1000 (millimeters) - Rangefinder Altitude above ground in meters, expressed as * 1000 (millimeters) - Extra altitude above ground in meters, expressed as * 1000 (millimeters) - - - The airspeed measured by sensors and IMU - Timestamp (milliseconds since system boot) - Airspeed estimate from IMU, cm/s - Pitot measured forward airpseed, cm/s - Hot wire anenometer measured airspeed, cm/s - Ultrasonic measured airspeed, cm/s - Angle of attack sensor, degrees * 10 - Yaw angle sensor, degrees * 10 - - - Backwards compatible version of SERIAL_UDB_EXTRA F17 format - SUE Feed Forward Gain - SUE Max Turn Rate when Navigating - SUE Max Turn Rate in Fly By Wire Mode - - - Backwards compatible version of SERIAL_UDB_EXTRA F18 format - SUE Angle of Attack Normal - SUE Angle of Attack Inverted - SUE Elevator Trim Normal - SUE Elevator Trim Inverted - SUE reference_speed - - - Backwards compatible version of SERIAL_UDB_EXTRA F19 format - SUE aileron output channel - SUE aileron reversed - SUE elevator output channel - SUE elevator reversed - SUE throttle output channel - SUE throttle reversed - SUE rudder output channel - SUE rudder reversed - - - Backwards compatible version of SERIAL_UDB_EXTRA F20 format - SUE Number of Input Channels - SUE UDB PWM Trim Value on Input 1 - SUE UDB PWM Trim Value on Input 2 - SUE UDB PWM Trim Value on Input 3 - SUE UDB PWM Trim Value on Input 4 - SUE UDB PWM Trim Value on Input 5 - SUE UDB PWM Trim Value on Input 6 - SUE UDB PWM Trim Value on Input 7 - SUE UDB PWM Trim Value on Input 8 - SUE UDB PWM Trim Value on Input 9 - SUE UDB PWM Trim Value on Input 10 - SUE UDB PWM Trim Value on Input 11 - SUE UDB PWM Trim Value on Input 12 - - - Backwards compatible version of SERIAL_UDB_EXTRA F21 format - SUE X accelerometer offset - SUE Y accelerometer offset - SUE Z accelerometer offset - SUE X gyro offset - SUE Y gyro offset - SUE Z gyro offset - - - Backwards compatible version of SERIAL_UDB_EXTRA F22 format - SUE X accelerometer at calibration time - SUE Y accelerometer at calibration time - SUE Z accelerometer at calibration time - SUE X gyro at calibration time - SUE Y gyro at calibration time - SUE Z gyro at calibration time - - - diff --git a/TelemetryManager/Inc/official_mavlink_2_library/message_definitions/minimal.xml b/TelemetryManager/Inc/official_mavlink_2_library/message_definitions/minimal.xml deleted file mode 100644 index 3adde421..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/message_definitions/minimal.xml +++ /dev/null @@ -1,725 +0,0 @@ - - - 3 - - - Micro air vehicle / autopilot classes. This identifies the individual model. - - Generic autopilot, full support for everything - - - Reserved for future use. - - - SLUGS autopilot, http://slugsuav.soe.ucsc.edu - - - ArduPilot - Plane/Copter/Rover/Sub/Tracker, https://ardupilot.org - - - OpenPilot, http://openpilot.org - - - Generic autopilot only supporting simple waypoints - - - Generic autopilot supporting waypoints and other simple navigation commands - - - Generic autopilot supporting the full mission command set - - - No valid autopilot, e.g. a GCS or other MAVLink component - - - PPZ UAV - http://nongnu.org/paparazzi - - - UAV Dev Board - - - FlexiPilot - - - PX4 Autopilot - http://px4.io/ - - - SMACCMPilot - http://smaccmpilot.org - - - AutoQuad -- http://autoquad.org - - - Armazila -- http://armazila.com - - - Aerob -- http://aerob.ru - - - ASLUAV autopilot -- http://www.asl.ethz.ch - - - SmartAP Autopilot - http://sky-drones.com - - - AirRails - http://uaventure.com - - - Fusion Reflex - https://fusion.engineering - - - - MAVLINK component type reported in HEARTBEAT message. Flight controllers must report the type of the vehicle on which they are mounted (e.g. MAV_TYPE_OCTOROTOR). All other components must report a value appropriate for their type (e.g. a camera must use MAV_TYPE_CAMERA). - - Generic micro air vehicle - - - Fixed wing aircraft. - - - Quadrotor - - - Coaxial helicopter - - - Normal helicopter with tail rotor. - - - Ground installation - - - Operator control unit / ground control station - - - Airship, controlled - - - Free balloon, uncontrolled - - - Rocket - - - Ground rover - - - Surface vessel, boat, ship - - - Submarine - - - Hexarotor - - - Octorotor - - - Tricopter - - - Flapping wing - - - Kite - - - Onboard companion controller - - - Two-rotor Tailsitter VTOL that additionally uses control surfaces in vertical operation. Note, value previously named MAV_TYPE_VTOL_DUOROTOR. - - - Quad-rotor Tailsitter VTOL using a V-shaped quad config in vertical operation. Note: value previously named MAV_TYPE_VTOL_QUADROTOR. - - - Tiltrotor VTOL. Fuselage and wings stay (nominally) horizontal in all flight phases. It able to tilt (some) rotors to provide thrust in cruise flight. - - - VTOL with separate fixed rotors for hover and cruise flight. Fuselage and wings stay (nominally) horizontal in all flight phases. - - - Tailsitter VTOL. Fuselage and wings orientation changes depending on flight phase: vertical for hover, horizontal for cruise. Use more specific VTOL MAV_TYPE_VTOL_DUOROTOR or MAV_TYPE_VTOL_QUADROTOR if appropriate. - - - Tiltwing VTOL. Fuselage stays horizontal in all flight phases. The whole wing, along with any attached engine, can tilt between vertical and horizontal mode. - - - - VTOL reserved 5 - - - Gimbal - - - ADSB system - - - Steerable, nonrigid airfoil - - - Dodecarotor - - - Camera - - - Charging station - - - FLARM collision avoidance system - - - Servo - - - Open Drone ID. See https://mavlink.io/en/services/opendroneid.html. - - - Decarotor - - - Battery - - - Parachute - - - Log - - - OSD - - - IMU - - - GPS - - - Winch - - - Generic multirotor that does not fit into a specific type or whose type is unknown - - - - These flags encode the MAV mode. - - 0b10000000 MAV safety set to armed. Motors are enabled / running / can start. Ready to fly. Additional note: this flag is to be ignore when sent in the command MAV_CMD_DO_SET_MODE and MAV_CMD_COMPONENT_ARM_DISARM shall be used instead. The flag can still be used to report the armed state. - - - 0b01000000 remote control input is enabled. - - - 0b00100000 hardware in the loop simulation. All motors / actuators are blocked, but internal software is full operational. - - - 0b00010000 system stabilizes electronically its attitude (and optionally position). It needs however further control inputs to move around. - - - 0b00001000 guided mode enabled, system flies waypoints / mission items. - - - 0b00000100 autonomous mode enabled, system finds its own goal positions. Guided flag can be set or not, depends on the actual implementation. - - - 0b00000010 system has a test mode enabled. This flag is intended for temporary system tests and should not be used for stable implementations. - - - 0b00000001 Reserved for future use. - - - - These values encode the bit positions of the decode position. These values can be used to read the value of a flag bit by combining the base_mode variable with AND with the flag position value. The result will be either 0 or 1, depending on if the flag is set or not. - - First bit: 10000000 - - - Second bit: 01000000 - - - Third bit: 00100000 - - - Fourth bit: 00010000 - - - Fifth bit: 00001000 - - - Sixth bit: 00000100 - - - Seventh bit: 00000010 - - - Eighth bit: 00000001 - - - - - Uninitialized system, state is unknown. - - - System is booting up. - - - System is calibrating and not flight-ready. - - - System is grounded and on standby. It can be launched any time. - - - System is active and might be already airborne. Motors are engaged. - - - System is in a non-normal flight mode (failsafe). It can however still navigate. - - - System is in a non-normal flight mode (failsafe). It lost control over parts or over the whole airframe. It is in mayday and going down. - - - System just initialized its power-down sequence, will shut down now. - - - System is terminating itself (failsafe or commanded). - - - - Component ids (values) for the different types and instances of onboard hardware/software that might make up a MAVLink system (autopilot, cameras, servos, GPS systems, avoidance systems etc.). - Components must use the appropriate ID in their source address when sending messages. Components can also use IDs to determine if they are the intended recipient of an incoming message. The MAV_COMP_ID_ALL value is used to indicate messages that must be processed by all components. - When creating new entries, components that can have multiple instances (e.g. cameras, servos etc.) should be allocated sequential values. An appropriate number of values should be left free after these components to allow the number of instances to be expanded. - - Target id (target_component) used to broadcast messages to all components of the receiving system. Components should attempt to process messages with this component ID and forward to components on any other interfaces. Note: This is not a valid *source* component id for a message. - - - System flight controller component ("autopilot"). Only one autopilot is expected in a particular system. - - - - Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. - - - Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. - - - Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. - - - Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. - - - Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. - - - Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. - - - Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. - - - Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. - - - Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. - - - Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. - - - Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. - - - Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. - - - Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. - - - Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. - - - Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. - - - Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. - - - Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. - - - Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. - - - Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. - - - Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. - - - Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. - - - Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. - - - Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. - - - Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. - - - Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. - - - Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. - - - Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. - - - Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. - - - Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. - - - Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. - - - Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. - - - Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. - - - Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. - - - Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. - - - Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. - - - Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. - - - Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. - - - Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. - - - Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. - - - Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. - - - Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. - - - Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. - - - Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. - - - Telemetry radio (e.g. SiK radio, or other component that emits RADIO_STATUS messages). - - - Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. - - - Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. - - - Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. - - - Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. - - - Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. - - - Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. - - - Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. - - - Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. - - - Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. - - - Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. - - - Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. - - - Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. - - - Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. - - - Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. - - - Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. - - - Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. - - - Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. - - - Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. - - - Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. - - - Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. - - - Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. - - - Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. - - - Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. - - - Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. - - - Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. - - - Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. - - - Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. - - - Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. - - - Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. - - - Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. - - - Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. - - - Camera #1. - - - Camera #2. - - - Camera #3. - - - Camera #4. - - - Camera #5. - - - Camera #6. - - - Servo #1. - - - Servo #2. - - - Servo #3. - - - Servo #4. - - - Servo #5. - - - Servo #6. - - - Servo #7. - - - Servo #8. - - - Servo #9. - - - Servo #10. - - - Servo #11. - - - Servo #12. - - - Servo #13. - - - Servo #14. - - - Gimbal #1. - - - Logging component. - - - Automatic Dependent Surveillance-Broadcast (ADS-B) component. - - - On Screen Display (OSD) devices for video links. - - - Generic autopilot peripheral component ID. Meant for devices that do not implement the parameter microservice. - - - All gimbals should use MAV_COMP_ID_GIMBAL. - Gimbal ID for QX1. - - - FLARM collision alert component. - - - Parachute component. - - - Winch component. - - - Gimbal #2. - - - Gimbal #3. - - - Gimbal #4 - - - Gimbal #5. - - - Gimbal #6. - - - Battery #1. - - - Battery #2. - - - CAN over MAVLink client. - - - Component that can generate/supply a mission flight plan (e.g. GCS or developer API). - - - Component that lives on the onboard computer (companion computer) and has some generic functionalities, such as settings system parameters and monitoring the status of some processes that don't directly speak mavlink and so on. - - - Component that lives on the onboard computer (companion computer) and has some generic functionalities, such as settings system parameters and monitoring the status of some processes that don't directly speak mavlink and so on. - - - Component that lives on the onboard computer (companion computer) and has some generic functionalities, such as settings system parameters and monitoring the status of some processes that don't directly speak mavlink and so on. - - - Component that lives on the onboard computer (companion computer) and has some generic functionalities, such as settings system parameters and monitoring the status of some processes that don't directly speak mavlink and so on. - - - Component that finds an optimal path between points based on a certain constraint (e.g. minimum snap, shortest path, cost, etc.). - - - Component that plans a collision free path between two points. - - - Component that provides position estimates using VIO techniques. - - - Component that manages pairing of vehicle and GCS. - - - Inertial Measurement Unit (IMU) #1. - - - Inertial Measurement Unit (IMU) #2. - - - Inertial Measurement Unit (IMU) #3. - - - GPS #1. - - - GPS #2. - - - Open Drone ID transmitter/receiver (Bluetooth/WiFi/Internet). - - - Open Drone ID transmitter/receiver (Bluetooth/WiFi/Internet). - - - Open Drone ID transmitter/receiver (Bluetooth/WiFi/Internet). - - - Component to bridge MAVLink to UDP (i.e. from a UART). - - - Component to bridge to UART (i.e. from UDP). - - - Component handling TUNNEL messages (e.g. vendor specific GUI of a component). - - - System control does not require a separate component ID. Instead, system commands should be sent with target_component=MAV_COMP_ID_ALL allowing the target component to use any appropriate component id. - Deprecated, don't use. Component for handling system messages (e.g. to ARM, takeoff, etc.). - - - - - - The heartbeat message shows that a system or component is present and responding. The type and autopilot fields (along with the message component id), allow the receiving system to treat further messages from this system appropriately (e.g. by laying out the user interface based on the autopilot). This microservice is documented at https://mavlink.io/en/services/heartbeat.html - Vehicle or component type. For a flight controller component the vehicle type (quadrotor, helicopter, etc.). For other components the component type (e.g. camera, gimbal, etc.). This should be used in preference to component id for identifying the component type. - Autopilot type / class. Use MAV_AUTOPILOT_INVALID for components that are not flight controllers. - System mode bitmap. - A bitfield for use for autopilot-specific flags - System status flag. - MAVLink version, not writable by user, gets added by protocol because of magic data type: uint8_t_mavlink_version - - - - - Version and capability of protocol version. This message can be requested with MAV_CMD_REQUEST_MESSAGE and is used as part of the handshaking to establish which MAVLink version should be used on the network. Every node should respond to a request for PROTOCOL_VERSION to enable the handshaking. Library implementers should consider adding this into the default decoding state machine to allow the protocol core to respond directly. - Currently active MAVLink version number * 100: v1.0 is 100, v2.0 is 200, etc. - Minimum MAVLink version supported - Maximum MAVLink version supported (set to the same value as version by default) - The first 8 bytes (not characters printed in hex!) of the git hash. - The first 8 bytes (not characters printed in hex!) of the git hash. - - - diff --git a/TelemetryManager/Inc/official_mavlink_2_library/message_definitions/paparazzi.xml b/TelemetryManager/Inc/official_mavlink_2_library/message_definitions/paparazzi.xml deleted file mode 100644 index 45c9ec55..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/message_definitions/paparazzi.xml +++ /dev/null @@ -1,38 +0,0 @@ - - - common.xml - 3 - - - - - - Message encoding a mission script item. This message is emitted upon a request for the next script item. - System ID - Component ID - Sequence - The name of the mission script, NULL terminated. - - - Request script item with the sequence number seq. The response of the system to this message should be a SCRIPT_ITEM message. - System ID - Component ID - Sequence - - - Request the overall list of mission items from the system/component. - System ID - Component ID - - - This message is emitted as response to SCRIPT_REQUEST_LIST by the MAV to get the number of mission scripts. - System ID - Component ID - Number of script items in the sequence - - - This message informs about the currently active SCRIPT. - Active Sequence - - - diff --git a/TelemetryManager/Inc/official_mavlink_2_library/message_definitions/python_array_test.xml b/TelemetryManager/Inc/official_mavlink_2_library/message_definitions/python_array_test.xml deleted file mode 100644 index 7e4b72e1..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/message_definitions/python_array_test.xml +++ /dev/null @@ -1,67 +0,0 @@ - - - - common.xml - - - Array test #0. - Stub field - Value array - Value array - Value array - Value array - - - Array test #1. - Value array - - - Array test #3. - Stub field - Value array - - - Array test #4. - Value array - Stub field - - - Array test #5. - Value array - Value array - - - Array test #6. - Stub field - Stub field - Stub field - Value array - Value array - Value array - Value array - Value array - Value array - Value array - Value array - Value array - - - Array test #7. - Value array - Value array - Value array - Value array - Value array - Value array - Value array - Value array - Value array - - - Array test #8. - Stub field - Value array - Value array - - - diff --git a/TelemetryManager/Inc/official_mavlink_2_library/message_definitions/standard.xml b/TelemetryManager/Inc/official_mavlink_2_library/message_definitions/standard.xml deleted file mode 100644 index e323b954..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/message_definitions/standard.xml +++ /dev/null @@ -1,10 +0,0 @@ - - - - minimal.xml - 0 - - - - - diff --git a/TelemetryManager/Inc/official_mavlink_2_library/message_definitions/storm32.xml b/TelemetryManager/Inc/official_mavlink_2_library/message_definitions/storm32.xml deleted file mode 100644 index e385eb48..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/message_definitions/storm32.xml +++ /dev/null @@ -1,433 +0,0 @@ - - - - ardupilotmega.xml - 1 - 1 - - - - - - - Registered for STorM32 gimbal controller. For communication with gimbal or camera. - - - Registered for STorM32 gimbal controller. For communication with gimbal or camera. - - - Registered for STorM32 gimbal controller. For communication with gimbal. - - - Registered for STorM32 gimbal controller. For communication with gimbal. - - - Registered for STorM32 gimbal controller. For communication with camera. - - - Registered for STorM32 gimbal controller. For communication with camera. - - - - - - STorM32 gimbal prearm check flags. - - STorM32 gimbal is in normal state. - - - The IMUs are healthy and working normally. - - - The motors are active and working normally. - - - The encoders are healthy and working normally. - - - A battery voltage is applied and is in range. - - - Virtual input channels are receiving data. - - - Mavlink messages are being received. - - - The STorM32Link data indicates QFix. - - - The STorM32Link is working. - - - The camera has been found and is connected. - - - The signal on the AUX0 input pin is low. - - - The signal on the AUX1 input pin is low. - - - The NTLogger is working normally. - - - - - STorM32 camera prearm check flags. - - The camera has been found and is connected. - - - - - - - Gimbal manager capability flags. - - The gimbal manager supports several profiles. - - - - - Flags for gimbal manager operation. Used for setting and reporting, unless specified otherwise. If a setting has been accepted by the gimbal manager is reported in the STORM32_GIMBAL_MANAGER_STATUS message. - - 0 = ignore. - - - Request to set RC input to active, or report RC input is active. Implies RC mixed. RC exclusive is achieved by setting all clients to inactive. - - - Request to set onboard/companion computer client to active, or report this client is active. - - - Request to set autopliot client to active, or report this client is active. - - - Request to set GCS client to active, or report this client is active. - - - Request to set camera client to active, or report this client is active. - - - Request to set GCS2 client to active, or report this client is active. - - - Request to set camera2 client to active, or report this client is active. - - - Request to set custom client to active, or report this client is active. - - - Request to set custom2 client to active, or report this client is active. - - - Request supervision. This flag is only for setting, it is not reported. - - - Release supervision. This flag is only for setting, it is not reported. - - - - - Gimbal manager client ID. In a prioritizing profile, the priorities are determined by the implementation; they could e.g. be custom1 > onboard > GCS > autopilot/camera > GCS2 > custom2. - - For convenience. - - - This is the onboard/companion computer client. - - - This is the autopilot client. - - - This is the GCS client. - - - This is the camera client. - - - This is the GCS2 client. - - - This is the camera2 client. - - - This is the custom client. - - - This is the custom2 client. - - - - - Gimbal manager profiles. Only standard profiles are defined. Any implementation can define its own profile(s) in addition, and should use enum values > 16. - - Default profile. Implementation specific. - - - Not supported/deprecated. - - - Profile with cooperative behavior. - - - Profile with exclusive behavior. - - - Profile with priority and cooperative behavior for equal priority. - - - Profile with priority and exclusive behavior for equal priority. - - - - - - Enumeration of possible shot modes. - - Undefined shot mode. Can be used to determine if qshots should be used or not. - - - Start normal gimbal operation. Is usually used to return back from a shot. - - - Load and keep safe gimbal position and stop stabilization. - - - Load neutral gimbal position and keep it while stabilizing. - - - Start mission with gimbal control. - - - Start RC gimbal control. - - - Start gimbal tracking the point specified by Lat, Lon, Alt. - - - Start gimbal tracking the system with specified system ID. - - - Start 2-point cable cam quick shot. - - - Start gimbal tracking the home location. - - - - - - - - Command to a gimbal manager to control the gimbal tilt and pan angles. It is possible to set combinations of the values below. E.g. an angle as well as a desired angular rate can be used to get to this angle at a certain angular rate, or an angular rate only will result in continuous turning. NaN is to be used to signal unset. A gimbal device is never to react to this command. - Pitch/tilt angle (positive: tilt up). NaN to be ignored. - Yaw/pan angle (positive: pan to the right). NaN to be ignored. The frame is determined by the GIMBAL_DEVICE_FLAGS_YAW_IN_xxx_FRAME flags. - Pitch/tilt rate (positive: tilt up). NaN to be ignored. - Yaw/pan rate (positive: pan to the right). NaN to be ignored. The frame is determined by the GIMBAL_DEVICE_FLAGS_YAW_IN_xxx_FRAME flags. - Gimbal device flags to be applied. - Gimbal manager flags to be applied. - Gimbal ID of the gimbal manager to address (component ID or 1-6 for non-MAVLink gimbal, 0 for all gimbals). Send command multiple times for more than one but not all gimbals. The client is copied into bits 8-15. - - - - - Command to configure a gimbal manager. A gimbal device is never to react to this command. The selected profile is reported in the STORM32_GIMBAL_MANAGER_STATUS message. - Gimbal manager profile (0 = default). - Gimbal ID of the gimbal manager to address (component ID or 1-6 for non-MAVLink gimbal, 0 for all gimbals). Send command multiple times for more than one but not all gimbals. - - - - - Command to set the shot manager mode. - Set shot mode. - Set shot state or command. The allowed values are specific to the selected shot mode. - - - - - RADIO_RC_CHANNELS flags (bitmask). - - Failsafe is active. - - - Indicates that the current frame has not been received. Channel values are frozen. - - - - RADIO_LINK_STATS flags (bitmask). - - Rssi are in negative dBm. Values 0..254 corresponds to 0..-254 dBm. - - - - - - - - - - Information about a gimbal manager. This message should be requested by a ground station using MAV_CMD_REQUEST_MESSAGE. It mirrors some fields of the GIMBAL_DEVICE_INFORMATION message, but not all. If the additional information is desired, also GIMBAL_DEVICE_INFORMATION should be requested. - Gimbal ID (component ID or 1-6 for non-MAVLink gimbal) that this gimbal manager is responsible for. - Gimbal device capability flags. Same flags as reported by GIMBAL_DEVICE_INFORMATION. The flag is only 16 bit wide, but stored in 32 bit, for backwards compatibility (high word is zero). - Gimbal manager capability flags. - Hardware minimum roll angle (positive: roll to the right). NaN if unknown. - Hardware maximum roll angle (positive: roll to the right). NaN if unknown. - Hardware minimum pitch/tilt angle (positive: tilt up). NaN if unknown. - Hardware maximum pitch/tilt angle (positive: tilt up). NaN if unknown. - Hardware minimum yaw/pan angle (positive: pan to the right, relative to the vehicle/gimbal base). NaN if unknown. - Hardware maximum yaw/pan angle (positive: pan to the right, relative to the vehicle/gimbal base). NaN if unknown. - - - - Message reporting the current status of a gimbal manager. This message should be broadcast at a low regular rate (e.g. 1 Hz, may be increase momentarily to e.g. 5 Hz for a period of 1 sec after a change). - Gimbal ID (component ID or 1-6 for non-MAVLink gimbal) that this gimbal manager is responsible for. - Client who is currently supervisor (0 = none). - Gimbal device flags currently applied. Same flags as reported by GIMBAL_DEVICE_ATTITUDE_STATUS. - Gimbal manager flags currently applied. - Profile currently applied (0 = default). - - - - Message to a gimbal manager to control the gimbal attitude. Angles and rates can be set to NaN according to use case. A gimbal device is never to react to this message. - System ID - Component ID - Gimbal ID of the gimbal manager to address (component ID or 1-6 for non-MAVLink gimbal, 0 for all gimbals). Send command multiple times for more than one but not all gimbals. - Client which is contacting the gimbal manager (must be set). - Gimbal device flags to be applied (UINT16_MAX to be ignored). Same flags as used in GIMBAL_DEVICE_SET_ATTITUDE. - Gimbal manager flags to be applied (0 to be ignored). - Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation). Set first element to NaN to be ignored. The frame is determined by the GIMBAL_DEVICE_FLAGS_YAW_IN_xxx_FRAME flags. - X component of angular velocity (positive: roll to the right). NaN to be ignored. - Y component of angular velocity (positive: tilt up). NaN to be ignored. - Z component of angular velocity (positive: pan to the right). NaN to be ignored. The frame is determined by the GIMBAL_DEVICE_FLAGS_YAW_IN_xxx_FRAME flags. - - - - Message to a gimbal manager to control the gimbal tilt and pan angles. Angles and rates can be set to NaN according to use case. A gimbal device is never to react to this message. - System ID - Component ID - Gimbal ID of the gimbal manager to address (component ID or 1-6 for non-MAVLink gimbal, 0 for all gimbals). Send command multiple times for more than one but not all gimbals. - Client which is contacting the gimbal manager (must be set). - Gimbal device flags to be applied (UINT16_MAX to be ignored). Same flags as used in GIMBAL_DEVICE_SET_ATTITUDE. - Gimbal manager flags to be applied (0 to be ignored). - Pitch/tilt angle (positive: tilt up). NaN to be ignored. - Yaw/pan angle (positive: pan the right). NaN to be ignored. The frame is determined by the GIMBAL_DEVICE_FLAGS_YAW_IN_xxx_FRAME flags. - Pitch/tilt angular rate (positive: tilt up). NaN to be ignored. - Yaw/pan angular rate (positive: pan to the right). NaN to be ignored. The frame is determined by the GIMBAL_DEVICE_FLAGS_YAW_IN_xxx_FRAME flags. - - - - Message to a gimbal manager to correct the gimbal roll angle. This message is typically used to manually correct for a tilted horizon in operation. A gimbal device is never to react to this message. - System ID - Component ID - Gimbal ID of the gimbal manager to address (component ID or 1-6 for non-MAVLink gimbal, 0 for all gimbals). Send command multiple times for more than one but not all gimbals. - Client which is contacting the gimbal manager (must be set). - Roll angle (positive to roll to the right). - - - - - - Information about the shot operation. - Current shot mode. - Current state in the shot. States are specific to the selected shot mode. - - - - - Radio channels. Supports up to 24 channels. Channel values are in centerd 13 bit format. Range is [-4096,4096], center is 0. Conversion to PWM is x * 5/32 + 1500. Should be emitted only by components with component id MAV_COMP_ID_TELEMETRY_RADIO. - Total number of RC channels being received. This can be larger than 24, indicating that more channels are available but not given in this message. - Radio channels status flags. - - RC channels. Channels above count should be set to 0, to benefit from MAVLink's zero padding. - - - Radio link statistics. Should be emitted only by components with component id MAV_COMP_ID_TELEMETRY_RADIO. Per default, rssi values are in MAVLink units: 0 represents weakest signal, 254 represents maximum signal; can be changed to dBm with the flag RADIO_LINK_STATS_FLAGS_RSSI_DBM. - Radio link statistics flags. - Values: 0..100. UINT8_MAX: invalid/unknown. - Rssi of antenna1. UINT8_MAX: invalid/unknown. - Noise on antenna1. Radio dependent. INT8_MAX: invalid/unknown. - Rssi of antenna2. UINT8_MAX: ignore/unknown, use rx_rssi1. - Noise on antenna2. Radio dependent. INT8_MAX: ignore/unknown, use rx_snr1. - 0: antenna1, 1: antenna2, UINT8_MAX: ignore, no Rx receive diversity, use rx_rssi1, rx_snr1. - 0: antenna1, 1: antenna2, UINT8_MAX: ignore, no Rx transmit diversity. - Values: 0..100. UINT8_MAX: invalid/unknown. - Rssi of antenna1. UINT8_MAX: invalid/unknown. - Noise on antenna1. Radio dependent. INT8_MAX: invalid/unknown. - Rssi of antenna2. UINT8_MAX: ignore/unknown, use tx_rssi1. - Noise on antenna2. Radio dependent. INT8_MAX: ignore/unknown, use tx_snr1. - 0: antenna1, 1: antenna2, UINT8_MAX: ignore, no Tx receive diversity, use tx_rssi1, tx_snr1. - 0: antenna1, 1: antenna2, UINT8_MAX: ignore, no Tx transmit diversity. - - - - Frsky SPort passthrough multi packet container. - Timestamp (time since system boot). - Number of passthrough packets in this message. - Passthrough packet buffer. A packet has 6 bytes: uint16_t id + uint32_t data. The array has space for 40 packets. - - - - Parameter multi param value container. - Total number of onboard parameters. - Index of the first onboard parameter in this array. - Number of onboard parameters in this array. - Flags. - Parameters buffer. Contains a series of variable length parameter blocks, one per parameter, with format as specifed elsewhere. - - - - diff --git a/TelemetryManager/Inc/official_mavlink_2_library/message_definitions/test.xml b/TelemetryManager/Inc/official_mavlink_2_library/message_definitions/test.xml deleted file mode 100644 index c6802074..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/message_definitions/test.xml +++ /dev/null @@ -1,31 +0,0 @@ - - - 3 - - - Test all field types - char - string - uint8_t - uint16_t - uint32_t - uint64_t - int8_t - int16_t - int32_t - int64_t - float - double - uint8_t_array - uint16_t_array - uint32_t_array - uint64_t_array - int8_t_array - int16_t_array - int32_t_array - int64_t_array - float_array - double_array - - - diff --git a/TelemetryManager/Inc/official_mavlink_2_library/message_definitions/uAvionix.xml b/TelemetryManager/Inc/official_mavlink_2_library/message_definitions/uAvionix.xml deleted file mode 100644 index f5c089e2..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/message_definitions/uAvionix.xml +++ /dev/null @@ -1,122 +0,0 @@ - - - - - - - common.xml - - - State flags for ADS-B transponder dynamic report - - - - - - - - Transceiver RF control flags for ADS-B transponder dynamic reports - - - - - - Status for ADS-B transponder dynamic input - - - - - - - - - Status flags for ADS-B transponder dynamic output - - - - - - - Definitions for aircraft size - - - - - - - - - - - - - - - - - - - GPS lataral offset encoding - - - - - - - - - - - GPS longitudinal offset encoding - - - - - Emergency status encoding - - - - - - - - - - - - - Static data to configure the ADS-B transponder (send within 10 sec of a POR and every 10 sec thereafter) - Vehicle address (24 bit) - Vehicle identifier (8 characters, null terminated, valid characters are A-Z, 0-9, " " only) - Transmitting vehicle type. See ADSB_EMITTER_TYPE enum - Aircraft length and width encoding (table 2-35 of DO-282B) - GPS antenna lateral offset (table 2-36 of DO-282B) - GPS antenna longitudinal offset from nose [if non-zero, take position (in meters) divide by 2 and add one] (table 2-37 DO-282B) - Aircraft stall speed in cm/s - ADS-B transponder receiver and transmit enable flags - - - Dynamic data used to generate ADS-B out transponder data (send at 5Hz) - UTC time in seconds since GPS epoch (Jan 6, 1980). If unknown set to UINT32_MAX - Latitude WGS84 (deg * 1E7). If unknown set to INT32_MAX - Longitude WGS84 (deg * 1E7). If unknown set to INT32_MAX - Altitude (WGS84). UP +ve. If unknown set to INT32_MAX - 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS, 5: RTK - Number of satellites visible. If unknown set to UINT8_MAX - Barometric pressure altitude (MSL) relative to a standard atmosphere of 1013.2 mBar and NOT bar corrected altitude (m * 1E-3). (up +ve). If unknown set to INT32_MAX - Horizontal accuracy in mm (m * 1E-3). If unknown set to UINT32_MAX - Vertical accuracy in cm. If unknown set to UINT16_MAX - Velocity accuracy in mm/s (m * 1E-3). If unknown set to UINT16_MAX - GPS vertical speed in cm/s. If unknown set to INT16_MAX - North-South velocity over ground in cm/s North +ve. If unknown set to INT16_MAX - East-West velocity over ground in cm/s East +ve. If unknown set to INT16_MAX - Emergency status - ADS-B transponder dynamic input state flags - Mode A code (typically 1200 [0x04B0] for VFR) - - - Transceiver heartbeat with health report (updated every 10s) - ADS-B transponder messages - - - diff --git a/TelemetryManager/Inc/official_mavlink_2_library/message_definitions/ualberta.xml b/TelemetryManager/Inc/official_mavlink_2_library/message_definitions/ualberta.xml deleted file mode 100644 index 5c674c54..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/message_definitions/ualberta.xml +++ /dev/null @@ -1,66 +0,0 @@ - - - common.xml - - - Available autopilot modes for ualberta uav - - Raw input pulse widts sent to output - - - Inputs are normalized using calibration, the converted back to raw pulse widths for output - - - - - - - Navigation filter mode - - - AHRS mode - - - INS/GPS initialization mode - - - INS/GPS mode - - - - Mode currently commanded by pilot - - - - Rotomotion mode - - - - - - Accelerometer and Gyro biases from the navigation filter - Timestamp (microseconds) - b_f[0] - b_f[1] - b_f[2] - b_f[0] - b_f[1] - b_f[2] - - - Complete set of calibration parameters for the radio - Aileron setpoints: left, center, right - Elevator setpoints: nose down, center, nose up - Rudder setpoints: nose left, center, nose right - Tail gyro mode/gain setpoints: heading hold, rate mode - Pitch curve setpoints (every 25%) - Throttle curve setpoints (every 25%) - - - System status specific to ualberta uav - System mode, see UALBERTA_AUTOPILOT_MODE ENUM - Navigation mode, see UALBERTA_NAV_MODE ENUM - Pilot mode, see UALBERTA_PILOT_MODE - - - diff --git a/TelemetryManager/Inc/official_mavlink_2_library/minimal/mavlink.h b/TelemetryManager/Inc/official_mavlink_2_library/minimal/mavlink.h deleted file mode 100644 index 7c07f172..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/minimal/mavlink.h +++ /dev/null @@ -1,34 +0,0 @@ -/** @file - * @brief MAVLink comm protocol built from minimal.xml - * @see http://mavlink.org - */ -#pragma once -#ifndef MAVLINK_H -#define MAVLINK_H - -#define MAVLINK_PRIMARY_XML_HASH 9153717747301418044 - -#ifndef MAVLINK_STX -#define MAVLINK_STX 253 -#endif - -#ifndef MAVLINK_ENDIAN -#define MAVLINK_ENDIAN MAVLINK_LITTLE_ENDIAN -#endif - -#ifndef MAVLINK_ALIGNED_FIELDS -#define MAVLINK_ALIGNED_FIELDS 1 -#endif - -#ifndef MAVLINK_CRC_EXTRA -#define MAVLINK_CRC_EXTRA 1 -#endif - -#ifndef MAVLINK_COMMAND_24BIT -#define MAVLINK_COMMAND_24BIT 1 -#endif - -#include "version.h" -#include "minimal.h" - -#endif // MAVLINK_H diff --git a/TelemetryManager/Inc/official_mavlink_2_library/minimal/mavlink_msg_heartbeat.h b/TelemetryManager/Inc/official_mavlink_2_library/minimal/mavlink_msg_heartbeat.h deleted file mode 100644 index 15d63931..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/minimal/mavlink_msg_heartbeat.h +++ /dev/null @@ -1,335 +0,0 @@ -#pragma once -// MESSAGE HEARTBEAT PACKING - -#define MAVLINK_MSG_ID_HEARTBEAT 0 - - -typedef struct __mavlink_heartbeat_t { - uint32_t custom_mode; /*< A bitfield for use for autopilot-specific flags*/ - uint8_t type; /*< Vehicle or component type. For a flight controller component the vehicle type (quadrotor, helicopter, etc.). For other components the component type (e.g. camera, gimbal, etc.). This should be used in preference to component id for identifying the component type.*/ - uint8_t autopilot; /*< Autopilot type / class. Use MAV_AUTOPILOT_INVALID for components that are not flight controllers.*/ - uint8_t base_mode; /*< System mode bitmap.*/ - uint8_t system_status; /*< System status flag.*/ - uint8_t mavlink_version; /*< MAVLink version, not writable by user, gets added by protocol because of magic data type: uint8_t_mavlink_version*/ -} mavlink_heartbeat_t; - -#define MAVLINK_MSG_ID_HEARTBEAT_LEN 9 -#define MAVLINK_MSG_ID_HEARTBEAT_MIN_LEN 9 -#define MAVLINK_MSG_ID_0_LEN 9 -#define MAVLINK_MSG_ID_0_MIN_LEN 9 - -#define MAVLINK_MSG_ID_HEARTBEAT_CRC 50 -#define MAVLINK_MSG_ID_0_CRC 50 - - - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_HEARTBEAT { \ - 0, \ - "HEARTBEAT", \ - 6, \ - { { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_heartbeat_t, type) }, \ - { "autopilot", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_heartbeat_t, autopilot) }, \ - { "base_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_heartbeat_t, base_mode) }, \ - { "custom_mode", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_heartbeat_t, custom_mode) }, \ - { "system_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_heartbeat_t, system_status) }, \ - { "mavlink_version", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_heartbeat_t, mavlink_version) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_HEARTBEAT { \ - "HEARTBEAT", \ - 6, \ - { { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_heartbeat_t, type) }, \ - { "autopilot", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_heartbeat_t, autopilot) }, \ - { "base_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_heartbeat_t, base_mode) }, \ - { "custom_mode", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_heartbeat_t, custom_mode) }, \ - { "system_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_heartbeat_t, system_status) }, \ - { "mavlink_version", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_heartbeat_t, mavlink_version) }, \ - } \ -} -#endif - -/** - * @brief Pack a heartbeat message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param type Vehicle or component type. For a flight controller component the vehicle type (quadrotor, helicopter, etc.). For other components the component type (e.g. camera, gimbal, etc.). This should be used in preference to component id for identifying the component type. - * @param autopilot Autopilot type / class. Use MAV_AUTOPILOT_INVALID for components that are not flight controllers. - * @param base_mode System mode bitmap. - * @param custom_mode A bitfield for use for autopilot-specific flags - * @param system_status System status flag. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_heartbeat_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t type, uint8_t autopilot, uint8_t base_mode, uint32_t custom_mode, uint8_t system_status) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_HEARTBEAT_LEN]; - _mav_put_uint32_t(buf, 0, custom_mode); - _mav_put_uint8_t(buf, 4, type); - _mav_put_uint8_t(buf, 5, autopilot); - _mav_put_uint8_t(buf, 6, base_mode); - _mav_put_uint8_t(buf, 7, system_status); - _mav_put_uint8_t(buf, 8, 3); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HEARTBEAT_LEN); -#else - mavlink_heartbeat_t packet; - packet.custom_mode = custom_mode; - packet.type = type; - packet.autopilot = autopilot; - packet.base_mode = base_mode; - packet.system_status = system_status; - packet.mavlink_version = 3; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HEARTBEAT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_HEARTBEAT; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HEARTBEAT_MIN_LEN, MAVLINK_MSG_ID_HEARTBEAT_LEN, MAVLINK_MSG_ID_HEARTBEAT_CRC); -} - -/** - * @brief Pack a heartbeat message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param type Vehicle or component type. For a flight controller component the vehicle type (quadrotor, helicopter, etc.). For other components the component type (e.g. camera, gimbal, etc.). This should be used in preference to component id for identifying the component type. - * @param autopilot Autopilot type / class. Use MAV_AUTOPILOT_INVALID for components that are not flight controllers. - * @param base_mode System mode bitmap. - * @param custom_mode A bitfield for use for autopilot-specific flags - * @param system_status System status flag. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_heartbeat_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t type,uint8_t autopilot,uint8_t base_mode,uint32_t custom_mode,uint8_t system_status) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_HEARTBEAT_LEN]; - _mav_put_uint32_t(buf, 0, custom_mode); - _mav_put_uint8_t(buf, 4, type); - _mav_put_uint8_t(buf, 5, autopilot); - _mav_put_uint8_t(buf, 6, base_mode); - _mav_put_uint8_t(buf, 7, system_status); - _mav_put_uint8_t(buf, 8, 3); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HEARTBEAT_LEN); -#else - mavlink_heartbeat_t packet; - packet.custom_mode = custom_mode; - packet.type = type; - packet.autopilot = autopilot; - packet.base_mode = base_mode; - packet.system_status = system_status; - packet.mavlink_version = 3; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HEARTBEAT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_HEARTBEAT; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HEARTBEAT_MIN_LEN, MAVLINK_MSG_ID_HEARTBEAT_LEN, MAVLINK_MSG_ID_HEARTBEAT_CRC); -} - -/** - * @brief Encode a heartbeat struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param heartbeat C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_heartbeat_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_heartbeat_t* heartbeat) -{ - return mavlink_msg_heartbeat_pack(system_id, component_id, msg, heartbeat->type, heartbeat->autopilot, heartbeat->base_mode, heartbeat->custom_mode, heartbeat->system_status); -} - -/** - * @brief Encode a heartbeat struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param heartbeat C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_heartbeat_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_heartbeat_t* heartbeat) -{ - return mavlink_msg_heartbeat_pack_chan(system_id, component_id, chan, msg, heartbeat->type, heartbeat->autopilot, heartbeat->base_mode, heartbeat->custom_mode, heartbeat->system_status); -} - -/** - * @brief Send a heartbeat message - * @param chan MAVLink channel to send the message - * - * @param type Vehicle or component type. For a flight controller component the vehicle type (quadrotor, helicopter, etc.). For other components the component type (e.g. camera, gimbal, etc.). This should be used in preference to component id for identifying the component type. - * @param autopilot Autopilot type / class. Use MAV_AUTOPILOT_INVALID for components that are not flight controllers. - * @param base_mode System mode bitmap. - * @param custom_mode A bitfield for use for autopilot-specific flags - * @param system_status System status flag. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_heartbeat_send(mavlink_channel_t chan, uint8_t type, uint8_t autopilot, uint8_t base_mode, uint32_t custom_mode, uint8_t system_status) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_HEARTBEAT_LEN]; - _mav_put_uint32_t(buf, 0, custom_mode); - _mav_put_uint8_t(buf, 4, type); - _mav_put_uint8_t(buf, 5, autopilot); - _mav_put_uint8_t(buf, 6, base_mode); - _mav_put_uint8_t(buf, 7, system_status); - _mav_put_uint8_t(buf, 8, 3); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HEARTBEAT, buf, MAVLINK_MSG_ID_HEARTBEAT_MIN_LEN, MAVLINK_MSG_ID_HEARTBEAT_LEN, MAVLINK_MSG_ID_HEARTBEAT_CRC); -#else - mavlink_heartbeat_t packet; - packet.custom_mode = custom_mode; - packet.type = type; - packet.autopilot = autopilot; - packet.base_mode = base_mode; - packet.system_status = system_status; - packet.mavlink_version = 3; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HEARTBEAT, (const char *)&packet, MAVLINK_MSG_ID_HEARTBEAT_MIN_LEN, MAVLINK_MSG_ID_HEARTBEAT_LEN, MAVLINK_MSG_ID_HEARTBEAT_CRC); -#endif -} - -/** - * @brief Send a heartbeat message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_heartbeat_send_struct(mavlink_channel_t chan, const mavlink_heartbeat_t* heartbeat) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_heartbeat_send(chan, heartbeat->type, heartbeat->autopilot, heartbeat->base_mode, heartbeat->custom_mode, heartbeat->system_status); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HEARTBEAT, (const char *)heartbeat, MAVLINK_MSG_ID_HEARTBEAT_MIN_LEN, MAVLINK_MSG_ID_HEARTBEAT_LEN, MAVLINK_MSG_ID_HEARTBEAT_CRC); -#endif -} - -#if MAVLINK_MSG_ID_HEARTBEAT_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_heartbeat_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t type, uint8_t autopilot, uint8_t base_mode, uint32_t custom_mode, uint8_t system_status) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, custom_mode); - _mav_put_uint8_t(buf, 4, type); - _mav_put_uint8_t(buf, 5, autopilot); - _mav_put_uint8_t(buf, 6, base_mode); - _mav_put_uint8_t(buf, 7, system_status); - _mav_put_uint8_t(buf, 8, 3); - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HEARTBEAT, buf, MAVLINK_MSG_ID_HEARTBEAT_MIN_LEN, MAVLINK_MSG_ID_HEARTBEAT_LEN, MAVLINK_MSG_ID_HEARTBEAT_CRC); -#else - mavlink_heartbeat_t *packet = (mavlink_heartbeat_t *)msgbuf; - packet->custom_mode = custom_mode; - packet->type = type; - packet->autopilot = autopilot; - packet->base_mode = base_mode; - packet->system_status = system_status; - packet->mavlink_version = 3; - - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HEARTBEAT, (const char *)packet, MAVLINK_MSG_ID_HEARTBEAT_MIN_LEN, MAVLINK_MSG_ID_HEARTBEAT_LEN, MAVLINK_MSG_ID_HEARTBEAT_CRC); -#endif -} -#endif - -#endif - -// MESSAGE HEARTBEAT UNPACKING - - -/** - * @brief Get field type from heartbeat message - * - * @return Vehicle or component type. For a flight controller component the vehicle type (quadrotor, helicopter, etc.). For other components the component type (e.g. camera, gimbal, etc.). This should be used in preference to component id for identifying the component type. - */ -static inline uint8_t mavlink_msg_heartbeat_get_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 4); -} - -/** - * @brief Get field autopilot from heartbeat message - * - * @return Autopilot type / class. Use MAV_AUTOPILOT_INVALID for components that are not flight controllers. - */ -static inline uint8_t mavlink_msg_heartbeat_get_autopilot(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 5); -} - -/** - * @brief Get field base_mode from heartbeat message - * - * @return System mode bitmap. - */ -static inline uint8_t mavlink_msg_heartbeat_get_base_mode(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 6); -} - -/** - * @brief Get field custom_mode from heartbeat message - * - * @return A bitfield for use for autopilot-specific flags - */ -static inline uint32_t mavlink_msg_heartbeat_get_custom_mode(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field system_status from heartbeat message - * - * @return System status flag. - */ -static inline uint8_t mavlink_msg_heartbeat_get_system_status(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 7); -} - -/** - * @brief Get field mavlink_version from heartbeat message - * - * @return MAVLink version, not writable by user, gets added by protocol because of magic data type: uint8_t_mavlink_version - */ -static inline uint8_t mavlink_msg_heartbeat_get_mavlink_version(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 8); -} - -/** - * @brief Decode a heartbeat message into a struct - * - * @param msg The message to decode - * @param heartbeat C-struct to decode the message contents into - */ -static inline void mavlink_msg_heartbeat_decode(const mavlink_message_t* msg, mavlink_heartbeat_t* heartbeat) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - heartbeat->custom_mode = mavlink_msg_heartbeat_get_custom_mode(msg); - heartbeat->type = mavlink_msg_heartbeat_get_type(msg); - heartbeat->autopilot = mavlink_msg_heartbeat_get_autopilot(msg); - heartbeat->base_mode = mavlink_msg_heartbeat_get_base_mode(msg); - heartbeat->system_status = mavlink_msg_heartbeat_get_system_status(msg); - heartbeat->mavlink_version = mavlink_msg_heartbeat_get_mavlink_version(msg); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_HEARTBEAT_LEN? msg->len : MAVLINK_MSG_ID_HEARTBEAT_LEN; - memset(heartbeat, 0, MAVLINK_MSG_ID_HEARTBEAT_LEN); - memcpy(heartbeat, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/minimal/mavlink_msg_protocol_version.h b/TelemetryManager/Inc/official_mavlink_2_library/minimal/mavlink_msg_protocol_version.h deleted file mode 100644 index 00ce8158..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/minimal/mavlink_msg_protocol_version.h +++ /dev/null @@ -1,306 +0,0 @@ -#pragma once -// MESSAGE PROTOCOL_VERSION PACKING - -#define MAVLINK_MSG_ID_PROTOCOL_VERSION 300 - - -typedef struct __mavlink_protocol_version_t { - uint16_t version; /*< Currently active MAVLink version number * 100: v1.0 is 100, v2.0 is 200, etc.*/ - uint16_t min_version; /*< Minimum MAVLink version supported*/ - uint16_t max_version; /*< Maximum MAVLink version supported (set to the same value as version by default)*/ - uint8_t spec_version_hash[8]; /*< The first 8 bytes (not characters printed in hex!) of the git hash.*/ - uint8_t library_version_hash[8]; /*< The first 8 bytes (not characters printed in hex!) of the git hash.*/ -} mavlink_protocol_version_t; - -#define MAVLINK_MSG_ID_PROTOCOL_VERSION_LEN 22 -#define MAVLINK_MSG_ID_PROTOCOL_VERSION_MIN_LEN 22 -#define MAVLINK_MSG_ID_300_LEN 22 -#define MAVLINK_MSG_ID_300_MIN_LEN 22 - -#define MAVLINK_MSG_ID_PROTOCOL_VERSION_CRC 217 -#define MAVLINK_MSG_ID_300_CRC 217 - -#define MAVLINK_MSG_PROTOCOL_VERSION_FIELD_SPEC_VERSION_HASH_LEN 8 -#define MAVLINK_MSG_PROTOCOL_VERSION_FIELD_LIBRARY_VERSION_HASH_LEN 8 - -#if MAVLINK_COMMAND_24BIT -#define MAVLINK_MESSAGE_INFO_PROTOCOL_VERSION { \ - 300, \ - "PROTOCOL_VERSION", \ - 5, \ - { { "version", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_protocol_version_t, version) }, \ - { "min_version", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_protocol_version_t, min_version) }, \ - { "max_version", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_protocol_version_t, max_version) }, \ - { "spec_version_hash", NULL, MAVLINK_TYPE_UINT8_T, 8, 6, offsetof(mavlink_protocol_version_t, spec_version_hash) }, \ - { "library_version_hash", NULL, MAVLINK_TYPE_UINT8_T, 8, 14, offsetof(mavlink_protocol_version_t, library_version_hash) }, \ - } \ -} -#else -#define MAVLINK_MESSAGE_INFO_PROTOCOL_VERSION { \ - "PROTOCOL_VERSION", \ - 5, \ - { { "version", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_protocol_version_t, version) }, \ - { "min_version", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_protocol_version_t, min_version) }, \ - { "max_version", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_protocol_version_t, max_version) }, \ - { "spec_version_hash", NULL, MAVLINK_TYPE_UINT8_T, 8, 6, offsetof(mavlink_protocol_version_t, spec_version_hash) }, \ - { "library_version_hash", NULL, MAVLINK_TYPE_UINT8_T, 8, 14, offsetof(mavlink_protocol_version_t, library_version_hash) }, \ - } \ -} -#endif - -/** - * @brief Pack a protocol_version message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param version Currently active MAVLink version number * 100: v1.0 is 100, v2.0 is 200, etc. - * @param min_version Minimum MAVLink version supported - * @param max_version Maximum MAVLink version supported (set to the same value as version by default) - * @param spec_version_hash The first 8 bytes (not characters printed in hex!) of the git hash. - * @param library_version_hash The first 8 bytes (not characters printed in hex!) of the git hash. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_protocol_version_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint16_t version, uint16_t min_version, uint16_t max_version, const uint8_t *spec_version_hash, const uint8_t *library_version_hash) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_PROTOCOL_VERSION_LEN]; - _mav_put_uint16_t(buf, 0, version); - _mav_put_uint16_t(buf, 2, min_version); - _mav_put_uint16_t(buf, 4, max_version); - _mav_put_uint8_t_array(buf, 6, spec_version_hash, 8); - _mav_put_uint8_t_array(buf, 14, library_version_hash, 8); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PROTOCOL_VERSION_LEN); -#else - mavlink_protocol_version_t packet; - packet.version = version; - packet.min_version = min_version; - packet.max_version = max_version; - mav_array_memcpy(packet.spec_version_hash, spec_version_hash, sizeof(uint8_t)*8); - mav_array_memcpy(packet.library_version_hash, library_version_hash, sizeof(uint8_t)*8); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PROTOCOL_VERSION_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_PROTOCOL_VERSION; - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PROTOCOL_VERSION_MIN_LEN, MAVLINK_MSG_ID_PROTOCOL_VERSION_LEN, MAVLINK_MSG_ID_PROTOCOL_VERSION_CRC); -} - -/** - * @brief Pack a protocol_version message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param version Currently active MAVLink version number * 100: v1.0 is 100, v2.0 is 200, etc. - * @param min_version Minimum MAVLink version supported - * @param max_version Maximum MAVLink version supported (set to the same value as version by default) - * @param spec_version_hash The first 8 bytes (not characters printed in hex!) of the git hash. - * @param library_version_hash The first 8 bytes (not characters printed in hex!) of the git hash. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_protocol_version_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint16_t version,uint16_t min_version,uint16_t max_version,const uint8_t *spec_version_hash,const uint8_t *library_version_hash) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_PROTOCOL_VERSION_LEN]; - _mav_put_uint16_t(buf, 0, version); - _mav_put_uint16_t(buf, 2, min_version); - _mav_put_uint16_t(buf, 4, max_version); - _mav_put_uint8_t_array(buf, 6, spec_version_hash, 8); - _mav_put_uint8_t_array(buf, 14, library_version_hash, 8); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PROTOCOL_VERSION_LEN); -#else - mavlink_protocol_version_t packet; - packet.version = version; - packet.min_version = min_version; - packet.max_version = max_version; - mav_array_memcpy(packet.spec_version_hash, spec_version_hash, sizeof(uint8_t)*8); - mav_array_memcpy(packet.library_version_hash, library_version_hash, sizeof(uint8_t)*8); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PROTOCOL_VERSION_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_PROTOCOL_VERSION; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_PROTOCOL_VERSION_MIN_LEN, MAVLINK_MSG_ID_PROTOCOL_VERSION_LEN, MAVLINK_MSG_ID_PROTOCOL_VERSION_CRC); -} - -/** - * @brief Encode a protocol_version struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param protocol_version C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_protocol_version_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_protocol_version_t* protocol_version) -{ - return mavlink_msg_protocol_version_pack(system_id, component_id, msg, protocol_version->version, protocol_version->min_version, protocol_version->max_version, protocol_version->spec_version_hash, protocol_version->library_version_hash); -} - -/** - * @brief Encode a protocol_version struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param protocol_version C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_protocol_version_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_protocol_version_t* protocol_version) -{ - return mavlink_msg_protocol_version_pack_chan(system_id, component_id, chan, msg, protocol_version->version, protocol_version->min_version, protocol_version->max_version, protocol_version->spec_version_hash, protocol_version->library_version_hash); -} - -/** - * @brief Send a protocol_version message - * @param chan MAVLink channel to send the message - * - * @param version Currently active MAVLink version number * 100: v1.0 is 100, v2.0 is 200, etc. - * @param min_version Minimum MAVLink version supported - * @param max_version Maximum MAVLink version supported (set to the same value as version by default) - * @param spec_version_hash The first 8 bytes (not characters printed in hex!) of the git hash. - * @param library_version_hash The first 8 bytes (not characters printed in hex!) of the git hash. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_protocol_version_send(mavlink_channel_t chan, uint16_t version, uint16_t min_version, uint16_t max_version, const uint8_t *spec_version_hash, const uint8_t *library_version_hash) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_PROTOCOL_VERSION_LEN]; - _mav_put_uint16_t(buf, 0, version); - _mav_put_uint16_t(buf, 2, min_version); - _mav_put_uint16_t(buf, 4, max_version); - _mav_put_uint8_t_array(buf, 6, spec_version_hash, 8); - _mav_put_uint8_t_array(buf, 14, library_version_hash, 8); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PROTOCOL_VERSION, buf, MAVLINK_MSG_ID_PROTOCOL_VERSION_MIN_LEN, MAVLINK_MSG_ID_PROTOCOL_VERSION_LEN, MAVLINK_MSG_ID_PROTOCOL_VERSION_CRC); -#else - mavlink_protocol_version_t packet; - packet.version = version; - packet.min_version = min_version; - packet.max_version = max_version; - mav_array_memcpy(packet.spec_version_hash, spec_version_hash, sizeof(uint8_t)*8); - mav_array_memcpy(packet.library_version_hash, library_version_hash, sizeof(uint8_t)*8); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PROTOCOL_VERSION, (const char *)&packet, MAVLINK_MSG_ID_PROTOCOL_VERSION_MIN_LEN, MAVLINK_MSG_ID_PROTOCOL_VERSION_LEN, MAVLINK_MSG_ID_PROTOCOL_VERSION_CRC); -#endif -} - -/** - * @brief Send a protocol_version message - * @param chan MAVLink channel to send the message - * @param struct The MAVLink struct to serialize - */ -static inline void mavlink_msg_protocol_version_send_struct(mavlink_channel_t chan, const mavlink_protocol_version_t* protocol_version) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - mavlink_msg_protocol_version_send(chan, protocol_version->version, protocol_version->min_version, protocol_version->max_version, protocol_version->spec_version_hash, protocol_version->library_version_hash); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PROTOCOL_VERSION, (const char *)protocol_version, MAVLINK_MSG_ID_PROTOCOL_VERSION_MIN_LEN, MAVLINK_MSG_ID_PROTOCOL_VERSION_LEN, MAVLINK_MSG_ID_PROTOCOL_VERSION_CRC); -#endif -} - -#if MAVLINK_MSG_ID_PROTOCOL_VERSION_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This variant of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_protocol_version_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint16_t version, uint16_t min_version, uint16_t max_version, const uint8_t *spec_version_hash, const uint8_t *library_version_hash) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint16_t(buf, 0, version); - _mav_put_uint16_t(buf, 2, min_version); - _mav_put_uint16_t(buf, 4, max_version); - _mav_put_uint8_t_array(buf, 6, spec_version_hash, 8); - _mav_put_uint8_t_array(buf, 14, library_version_hash, 8); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PROTOCOL_VERSION, buf, MAVLINK_MSG_ID_PROTOCOL_VERSION_MIN_LEN, MAVLINK_MSG_ID_PROTOCOL_VERSION_LEN, MAVLINK_MSG_ID_PROTOCOL_VERSION_CRC); -#else - mavlink_protocol_version_t *packet = (mavlink_protocol_version_t *)msgbuf; - packet->version = version; - packet->min_version = min_version; - packet->max_version = max_version; - mav_array_memcpy(packet->spec_version_hash, spec_version_hash, sizeof(uint8_t)*8); - mav_array_memcpy(packet->library_version_hash, library_version_hash, sizeof(uint8_t)*8); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PROTOCOL_VERSION, (const char *)packet, MAVLINK_MSG_ID_PROTOCOL_VERSION_MIN_LEN, MAVLINK_MSG_ID_PROTOCOL_VERSION_LEN, MAVLINK_MSG_ID_PROTOCOL_VERSION_CRC); -#endif -} -#endif - -#endif - -// MESSAGE PROTOCOL_VERSION UNPACKING - - -/** - * @brief Get field version from protocol_version message - * - * @return Currently active MAVLink version number * 100: v1.0 is 100, v2.0 is 200, etc. - */ -static inline uint16_t mavlink_msg_protocol_version_get_version(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 0); -} - -/** - * @brief Get field min_version from protocol_version message - * - * @return Minimum MAVLink version supported - */ -static inline uint16_t mavlink_msg_protocol_version_get_min_version(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 2); -} - -/** - * @brief Get field max_version from protocol_version message - * - * @return Maximum MAVLink version supported (set to the same value as version by default) - */ -static inline uint16_t mavlink_msg_protocol_version_get_max_version(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 4); -} - -/** - * @brief Get field spec_version_hash from protocol_version message - * - * @return The first 8 bytes (not characters printed in hex!) of the git hash. - */ -static inline uint16_t mavlink_msg_protocol_version_get_spec_version_hash(const mavlink_message_t* msg, uint8_t *spec_version_hash) -{ - return _MAV_RETURN_uint8_t_array(msg, spec_version_hash, 8, 6); -} - -/** - * @brief Get field library_version_hash from protocol_version message - * - * @return The first 8 bytes (not characters printed in hex!) of the git hash. - */ -static inline uint16_t mavlink_msg_protocol_version_get_library_version_hash(const mavlink_message_t* msg, uint8_t *library_version_hash) -{ - return _MAV_RETURN_uint8_t_array(msg, library_version_hash, 8, 14); -} - -/** - * @brief Decode a protocol_version message into a struct - * - * @param msg The message to decode - * @param protocol_version C-struct to decode the message contents into - */ -static inline void mavlink_msg_protocol_version_decode(const mavlink_message_t* msg, mavlink_protocol_version_t* protocol_version) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - protocol_version->version = mavlink_msg_protocol_version_get_version(msg); - protocol_version->min_version = mavlink_msg_protocol_version_get_min_version(msg); - protocol_version->max_version = mavlink_msg_protocol_version_get_max_version(msg); - mavlink_msg_protocol_version_get_spec_version_hash(msg, protocol_version->spec_version_hash); - mavlink_msg_protocol_version_get_library_version_hash(msg, protocol_version->library_version_hash); -#else - uint8_t len = msg->len < MAVLINK_MSG_ID_PROTOCOL_VERSION_LEN? msg->len : MAVLINK_MSG_ID_PROTOCOL_VERSION_LEN; - memset(protocol_version, 0, MAVLINK_MSG_ID_PROTOCOL_VERSION_LEN); - memcpy(protocol_version, _MAV_PAYLOAD(msg), len); -#endif -} diff --git a/TelemetryManager/Inc/official_mavlink_2_library/minimal/minimal.h b/TelemetryManager/Inc/official_mavlink_2_library/minimal/minimal.h deleted file mode 100644 index 6c055c87..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/minimal/minimal.h +++ /dev/null @@ -1,347 +0,0 @@ -/** @file - * @brief MAVLink comm protocol generated from minimal.xml - * @see http://mavlink.org - */ -#pragma once -#ifndef MAVLINK_MINIMAL_H -#define MAVLINK_MINIMAL_H - -#ifndef MAVLINK_H - #error Wrong include order: MAVLINK_MINIMAL.H MUST NOT BE DIRECTLY USED. Include mavlink.h from the same directory instead or set ALL AND EVERY defines from MAVLINK.H manually accordingly, including the #define MAVLINK_H call. -#endif - -#define MAVLINK_MINIMAL_XML_HASH 9153717747301418044 - -#ifdef __cplusplus -extern "C" { -#endif - -// MESSAGE LENGTHS AND CRCS - -#ifndef MAVLINK_MESSAGE_LENGTHS -#define MAVLINK_MESSAGE_LENGTHS {} -#endif - -#ifndef MAVLINK_MESSAGE_CRCS -#define MAVLINK_MESSAGE_CRCS {{0, 50, 9, 9, 0, 0, 0}, {300, 217, 22, 22, 0, 0, 0}} -#endif - -#include "../protocol.h" - -#define MAVLINK_ENABLED_MINIMAL - -// ENUM DEFINITIONS - - -/** @brief Micro air vehicle / autopilot classes. This identifies the individual model. */ -#ifndef HAVE_ENUM_MAV_AUTOPILOT -#define HAVE_ENUM_MAV_AUTOPILOT -typedef enum MAV_AUTOPILOT -{ - MAV_AUTOPILOT_GENERIC=0, /* Generic autopilot, full support for everything | */ - MAV_AUTOPILOT_RESERVED=1, /* Reserved for future use. | */ - MAV_AUTOPILOT_SLUGS=2, /* SLUGS autopilot, http://slugsuav.soe.ucsc.edu | */ - MAV_AUTOPILOT_ARDUPILOTMEGA=3, /* ArduPilot - Plane/Copter/Rover/Sub/Tracker, https://ardupilot.org | */ - MAV_AUTOPILOT_OPENPILOT=4, /* OpenPilot, http://openpilot.org | */ - MAV_AUTOPILOT_GENERIC_WAYPOINTS_ONLY=5, /* Generic autopilot only supporting simple waypoints | */ - MAV_AUTOPILOT_GENERIC_WAYPOINTS_AND_SIMPLE_NAVIGATION_ONLY=6, /* Generic autopilot supporting waypoints and other simple navigation commands | */ - MAV_AUTOPILOT_GENERIC_MISSION_FULL=7, /* Generic autopilot supporting the full mission command set | */ - MAV_AUTOPILOT_INVALID=8, /* No valid autopilot, e.g. a GCS or other MAVLink component | */ - MAV_AUTOPILOT_PPZ=9, /* PPZ UAV - http://nongnu.org/paparazzi | */ - MAV_AUTOPILOT_UDB=10, /* UAV Dev Board | */ - MAV_AUTOPILOT_FP=11, /* FlexiPilot | */ - MAV_AUTOPILOT_PX4=12, /* PX4 Autopilot - http://px4.io/ | */ - MAV_AUTOPILOT_SMACCMPILOT=13, /* SMACCMPilot - http://smaccmpilot.org | */ - MAV_AUTOPILOT_AUTOQUAD=14, /* AutoQuad -- http://autoquad.org | */ - MAV_AUTOPILOT_ARMAZILA=15, /* Armazila -- http://armazila.com | */ - MAV_AUTOPILOT_AEROB=16, /* Aerob -- http://aerob.ru | */ - MAV_AUTOPILOT_ASLUAV=17, /* ASLUAV autopilot -- http://www.asl.ethz.ch | */ - MAV_AUTOPILOT_SMARTAP=18, /* SmartAP Autopilot - http://sky-drones.com | */ - MAV_AUTOPILOT_AIRRAILS=19, /* AirRails - http://uaventure.com | */ - MAV_AUTOPILOT_REFLEX=20, /* Fusion Reflex - https://fusion.engineering | */ - MAV_AUTOPILOT_ENUM_END=21, /* | */ -} MAV_AUTOPILOT; -#endif - -/** @brief MAVLINK component type reported in HEARTBEAT message. Flight controllers must report the type of the vehicle on which they are mounted (e.g. MAV_TYPE_OCTOROTOR). All other components must report a value appropriate for their type (e.g. a camera must use MAV_TYPE_CAMERA). */ -#ifndef HAVE_ENUM_MAV_TYPE -#define HAVE_ENUM_MAV_TYPE -typedef enum MAV_TYPE -{ - MAV_TYPE_GENERIC=0, /* Generic micro air vehicle | */ - MAV_TYPE_FIXED_WING=1, /* Fixed wing aircraft. | */ - MAV_TYPE_QUADROTOR=2, /* Quadrotor | */ - MAV_TYPE_COAXIAL=3, /* Coaxial helicopter | */ - MAV_TYPE_HELICOPTER=4, /* Normal helicopter with tail rotor. | */ - MAV_TYPE_ANTENNA_TRACKER=5, /* Ground installation | */ - MAV_TYPE_GCS=6, /* Operator control unit / ground control station | */ - MAV_TYPE_AIRSHIP=7, /* Airship, controlled | */ - MAV_TYPE_FREE_BALLOON=8, /* Free balloon, uncontrolled | */ - MAV_TYPE_ROCKET=9, /* Rocket | */ - MAV_TYPE_GROUND_ROVER=10, /* Ground rover | */ - MAV_TYPE_SURFACE_BOAT=11, /* Surface vessel, boat, ship | */ - MAV_TYPE_SUBMARINE=12, /* Submarine | */ - MAV_TYPE_HEXAROTOR=13, /* Hexarotor | */ - MAV_TYPE_OCTOROTOR=14, /* Octorotor | */ - MAV_TYPE_TRICOPTER=15, /* Tricopter | */ - MAV_TYPE_FLAPPING_WING=16, /* Flapping wing | */ - MAV_TYPE_KITE=17, /* Kite | */ - MAV_TYPE_ONBOARD_CONTROLLER=18, /* Onboard companion controller | */ - MAV_TYPE_VTOL_TAILSITTER_DUOROTOR=19, /* Two-rotor Tailsitter VTOL that additionally uses control surfaces in vertical operation. Note, value previously named MAV_TYPE_VTOL_DUOROTOR. | */ - MAV_TYPE_VTOL_TAILSITTER_QUADROTOR=20, /* Quad-rotor Tailsitter VTOL using a V-shaped quad config in vertical operation. Note: value previously named MAV_TYPE_VTOL_QUADROTOR. | */ - MAV_TYPE_VTOL_TILTROTOR=21, /* Tiltrotor VTOL. Fuselage and wings stay (nominally) horizontal in all flight phases. It able to tilt (some) rotors to provide thrust in cruise flight. | */ - MAV_TYPE_VTOL_FIXEDROTOR=22, /* VTOL with separate fixed rotors for hover and cruise flight. Fuselage and wings stay (nominally) horizontal in all flight phases. | */ - MAV_TYPE_VTOL_TAILSITTER=23, /* Tailsitter VTOL. Fuselage and wings orientation changes depending on flight phase: vertical for hover, horizontal for cruise. Use more specific VTOL MAV_TYPE_VTOL_DUOROTOR or MAV_TYPE_VTOL_QUADROTOR if appropriate. | */ - MAV_TYPE_VTOL_TILTWING=24, /* Tiltwing VTOL. Fuselage stays horizontal in all flight phases. The whole wing, along with any attached engine, can tilt between vertical and horizontal mode. | */ - MAV_TYPE_VTOL_RESERVED5=25, /* VTOL reserved 5 | */ - MAV_TYPE_GIMBAL=26, /* Gimbal | */ - MAV_TYPE_ADSB=27, /* ADSB system | */ - MAV_TYPE_PARAFOIL=28, /* Steerable, nonrigid airfoil | */ - MAV_TYPE_DODECAROTOR=29, /* Dodecarotor | */ - MAV_TYPE_CAMERA=30, /* Camera | */ - MAV_TYPE_CHARGING_STATION=31, /* Charging station | */ - MAV_TYPE_FLARM=32, /* FLARM collision avoidance system | */ - MAV_TYPE_SERVO=33, /* Servo | */ - MAV_TYPE_ODID=34, /* Open Drone ID. See https://mavlink.io/en/services/opendroneid.html. | */ - MAV_TYPE_DECAROTOR=35, /* Decarotor | */ - MAV_TYPE_BATTERY=36, /* Battery | */ - MAV_TYPE_PARACHUTE=37, /* Parachute | */ - MAV_TYPE_LOG=38, /* Log | */ - MAV_TYPE_OSD=39, /* OSD | */ - MAV_TYPE_IMU=40, /* IMU | */ - MAV_TYPE_GPS=41, /* GPS | */ - MAV_TYPE_WINCH=42, /* Winch | */ - MAV_TYPE_GENERIC_MULTIROTOR=43, /* Generic multirotor that does not fit into a specific type or whose type is unknown | */ - MAV_TYPE_ENUM_END=44, /* | */ -} MAV_TYPE; -#endif - -/** @brief These flags encode the MAV mode. */ -#ifndef HAVE_ENUM_MAV_MODE_FLAG -#define HAVE_ENUM_MAV_MODE_FLAG -typedef enum MAV_MODE_FLAG -{ - MAV_MODE_FLAG_CUSTOM_MODE_ENABLED=1, /* 0b00000001 Reserved for future use. | */ - MAV_MODE_FLAG_TEST_ENABLED=2, /* 0b00000010 system has a test mode enabled. This flag is intended for temporary system tests and should not be used for stable implementations. | */ - MAV_MODE_FLAG_AUTO_ENABLED=4, /* 0b00000100 autonomous mode enabled, system finds its own goal positions. Guided flag can be set or not, depends on the actual implementation. | */ - MAV_MODE_FLAG_GUIDED_ENABLED=8, /* 0b00001000 guided mode enabled, system flies waypoints / mission items. | */ - MAV_MODE_FLAG_STABILIZE_ENABLED=16, /* 0b00010000 system stabilizes electronically its attitude (and optionally position). It needs however further control inputs to move around. | */ - MAV_MODE_FLAG_HIL_ENABLED=32, /* 0b00100000 hardware in the loop simulation. All motors / actuators are blocked, but internal software is full operational. | */ - MAV_MODE_FLAG_MANUAL_INPUT_ENABLED=64, /* 0b01000000 remote control input is enabled. | */ - MAV_MODE_FLAG_SAFETY_ARMED=128, /* 0b10000000 MAV safety set to armed. Motors are enabled / running / can start. Ready to fly. Additional note: this flag is to be ignore when sent in the command MAV_CMD_DO_SET_MODE and MAV_CMD_COMPONENT_ARM_DISARM shall be used instead. The flag can still be used to report the armed state. | */ - MAV_MODE_FLAG_ENUM_END=129, /* | */ -} MAV_MODE_FLAG; -#endif - -/** @brief These values encode the bit positions of the decode position. These values can be used to read the value of a flag bit by combining the base_mode variable with AND with the flag position value. The result will be either 0 or 1, depending on if the flag is set or not. */ -#ifndef HAVE_ENUM_MAV_MODE_FLAG_DECODE_POSITION -#define HAVE_ENUM_MAV_MODE_FLAG_DECODE_POSITION -typedef enum MAV_MODE_FLAG_DECODE_POSITION -{ - MAV_MODE_FLAG_DECODE_POSITION_CUSTOM_MODE=1, /* Eighth bit: 00000001 | */ - MAV_MODE_FLAG_DECODE_POSITION_TEST=2, /* Seventh bit: 00000010 | */ - MAV_MODE_FLAG_DECODE_POSITION_AUTO=4, /* Sixth bit: 00000100 | */ - MAV_MODE_FLAG_DECODE_POSITION_GUIDED=8, /* Fifth bit: 00001000 | */ - MAV_MODE_FLAG_DECODE_POSITION_STABILIZE=16, /* Fourth bit: 00010000 | */ - MAV_MODE_FLAG_DECODE_POSITION_HIL=32, /* Third bit: 00100000 | */ - MAV_MODE_FLAG_DECODE_POSITION_MANUAL=64, /* Second bit: 01000000 | */ - MAV_MODE_FLAG_DECODE_POSITION_SAFETY=128, /* First bit: 10000000 | */ - MAV_MODE_FLAG_DECODE_POSITION_ENUM_END=129, /* | */ -} MAV_MODE_FLAG_DECODE_POSITION; -#endif - -/** @brief */ -#ifndef HAVE_ENUM_MAV_STATE -#define HAVE_ENUM_MAV_STATE -typedef enum MAV_STATE -{ - MAV_STATE_UNINIT=0, /* Uninitialized system, state is unknown. | */ - MAV_STATE_BOOT=1, /* System is booting up. | */ - MAV_STATE_CALIBRATING=2, /* System is calibrating and not flight-ready. | */ - MAV_STATE_STANDBY=3, /* System is grounded and on standby. It can be launched any time. | */ - MAV_STATE_ACTIVE=4, /* System is active and might be already airborne. Motors are engaged. | */ - MAV_STATE_CRITICAL=5, /* System is in a non-normal flight mode (failsafe). It can however still navigate. | */ - MAV_STATE_EMERGENCY=6, /* System is in a non-normal flight mode (failsafe). It lost control over parts or over the whole airframe. It is in mayday and going down. | */ - MAV_STATE_POWEROFF=7, /* System just initialized its power-down sequence, will shut down now. | */ - MAV_STATE_FLIGHT_TERMINATION=8, /* System is terminating itself (failsafe or commanded). | */ - MAV_STATE_ENUM_END=9, /* | */ -} MAV_STATE; -#endif - -/** @brief Component ids (values) for the different types and instances of onboard hardware/software that might make up a MAVLink system (autopilot, cameras, servos, GPS systems, avoidance systems etc.). - Components must use the appropriate ID in their source address when sending messages. Components can also use IDs to determine if they are the intended recipient of an incoming message. The MAV_COMP_ID_ALL value is used to indicate messages that must be processed by all components. - When creating new entries, components that can have multiple instances (e.g. cameras, servos etc.) should be allocated sequential values. An appropriate number of values should be left free after these components to allow the number of instances to be expanded. */ -#ifndef HAVE_ENUM_MAV_COMPONENT -#define HAVE_ENUM_MAV_COMPONENT -typedef enum MAV_COMPONENT -{ - MAV_COMP_ID_ALL=0, /* Target id (target_component) used to broadcast messages to all components of the receiving system. Components should attempt to process messages with this component ID and forward to components on any other interfaces. Note: This is not a valid *source* component id for a message. | */ - MAV_COMP_ID_AUTOPILOT1=1, /* System flight controller component ("autopilot"). Only one autopilot is expected in a particular system. | */ - MAV_COMP_ID_USER1=25, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ - MAV_COMP_ID_USER2=26, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ - MAV_COMP_ID_USER3=27, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ - MAV_COMP_ID_USER4=28, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ - MAV_COMP_ID_USER5=29, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ - MAV_COMP_ID_USER6=30, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ - MAV_COMP_ID_USER7=31, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ - MAV_COMP_ID_USER8=32, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ - MAV_COMP_ID_USER9=33, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ - MAV_COMP_ID_USER10=34, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ - MAV_COMP_ID_USER11=35, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ - MAV_COMP_ID_USER12=36, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ - MAV_COMP_ID_USER13=37, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ - MAV_COMP_ID_USER14=38, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ - MAV_COMP_ID_USER15=39, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ - MAV_COMP_ID_USER16=40, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ - MAV_COMP_ID_USER17=41, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ - MAV_COMP_ID_USER18=42, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ - MAV_COMP_ID_USER19=43, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ - MAV_COMP_ID_USER20=44, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ - MAV_COMP_ID_USER21=45, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ - MAV_COMP_ID_USER22=46, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ - MAV_COMP_ID_USER23=47, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ - MAV_COMP_ID_USER24=48, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ - MAV_COMP_ID_USER25=49, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ - MAV_COMP_ID_USER26=50, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ - MAV_COMP_ID_USER27=51, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ - MAV_COMP_ID_USER28=52, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ - MAV_COMP_ID_USER29=53, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ - MAV_COMP_ID_USER30=54, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ - MAV_COMP_ID_USER31=55, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ - MAV_COMP_ID_USER32=56, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ - MAV_COMP_ID_USER33=57, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ - MAV_COMP_ID_USER34=58, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ - MAV_COMP_ID_USER35=59, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ - MAV_COMP_ID_USER36=60, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ - MAV_COMP_ID_USER37=61, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ - MAV_COMP_ID_USER38=62, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ - MAV_COMP_ID_USER39=63, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ - MAV_COMP_ID_USER40=64, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ - MAV_COMP_ID_USER41=65, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ - MAV_COMP_ID_USER42=66, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ - MAV_COMP_ID_USER43=67, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ - MAV_COMP_ID_TELEMETRY_RADIO=68, /* Telemetry radio (e.g. SiK radio, or other component that emits RADIO_STATUS messages). | */ - MAV_COMP_ID_USER45=69, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ - MAV_COMP_ID_USER46=70, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ - MAV_COMP_ID_USER47=71, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ - MAV_COMP_ID_USER48=72, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ - MAV_COMP_ID_USER49=73, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ - MAV_COMP_ID_USER50=74, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ - MAV_COMP_ID_USER51=75, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ - MAV_COMP_ID_USER52=76, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ - MAV_COMP_ID_USER53=77, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ - MAV_COMP_ID_USER54=78, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ - MAV_COMP_ID_USER55=79, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ - MAV_COMP_ID_USER56=80, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ - MAV_COMP_ID_USER57=81, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ - MAV_COMP_ID_USER58=82, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ - MAV_COMP_ID_USER59=83, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ - MAV_COMP_ID_USER60=84, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ - MAV_COMP_ID_USER61=85, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ - MAV_COMP_ID_USER62=86, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ - MAV_COMP_ID_USER63=87, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ - MAV_COMP_ID_USER64=88, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ - MAV_COMP_ID_USER65=89, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ - MAV_COMP_ID_USER66=90, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ - MAV_COMP_ID_USER67=91, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ - MAV_COMP_ID_USER68=92, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ - MAV_COMP_ID_USER69=93, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ - MAV_COMP_ID_USER70=94, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ - MAV_COMP_ID_USER71=95, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ - MAV_COMP_ID_USER72=96, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ - MAV_COMP_ID_USER73=97, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ - MAV_COMP_ID_USER74=98, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ - MAV_COMP_ID_USER75=99, /* Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. | */ - MAV_COMP_ID_CAMERA=100, /* Camera #1. | */ - MAV_COMP_ID_CAMERA2=101, /* Camera #2. | */ - MAV_COMP_ID_CAMERA3=102, /* Camera #3. | */ - MAV_COMP_ID_CAMERA4=103, /* Camera #4. | */ - MAV_COMP_ID_CAMERA5=104, /* Camera #5. | */ - MAV_COMP_ID_CAMERA6=105, /* Camera #6. | */ - MAV_COMP_ID_SERVO1=140, /* Servo #1. | */ - MAV_COMP_ID_SERVO2=141, /* Servo #2. | */ - MAV_COMP_ID_SERVO3=142, /* Servo #3. | */ - MAV_COMP_ID_SERVO4=143, /* Servo #4. | */ - MAV_COMP_ID_SERVO5=144, /* Servo #5. | */ - MAV_COMP_ID_SERVO6=145, /* Servo #6. | */ - MAV_COMP_ID_SERVO7=146, /* Servo #7. | */ - MAV_COMP_ID_SERVO8=147, /* Servo #8. | */ - MAV_COMP_ID_SERVO9=148, /* Servo #9. | */ - MAV_COMP_ID_SERVO10=149, /* Servo #10. | */ - MAV_COMP_ID_SERVO11=150, /* Servo #11. | */ - MAV_COMP_ID_SERVO12=151, /* Servo #12. | */ - MAV_COMP_ID_SERVO13=152, /* Servo #13. | */ - MAV_COMP_ID_SERVO14=153, /* Servo #14. | */ - MAV_COMP_ID_GIMBAL=154, /* Gimbal #1. | */ - MAV_COMP_ID_LOG=155, /* Logging component. | */ - MAV_COMP_ID_ADSB=156, /* Automatic Dependent Surveillance-Broadcast (ADS-B) component. | */ - MAV_COMP_ID_OSD=157, /* On Screen Display (OSD) devices for video links. | */ - MAV_COMP_ID_PERIPHERAL=158, /* Generic autopilot peripheral component ID. Meant for devices that do not implement the parameter microservice. | */ - MAV_COMP_ID_QX1_GIMBAL=159, /* Gimbal ID for QX1. | */ - MAV_COMP_ID_FLARM=160, /* FLARM collision alert component. | */ - MAV_COMP_ID_PARACHUTE=161, /* Parachute component. | */ - MAV_COMP_ID_WINCH=169, /* Winch component. | */ - MAV_COMP_ID_GIMBAL2=171, /* Gimbal #2. | */ - MAV_COMP_ID_GIMBAL3=172, /* Gimbal #3. | */ - MAV_COMP_ID_GIMBAL4=173, /* Gimbal #4 | */ - MAV_COMP_ID_GIMBAL5=174, /* Gimbal #5. | */ - MAV_COMP_ID_GIMBAL6=175, /* Gimbal #6. | */ - MAV_COMP_ID_BATTERY=180, /* Battery #1. | */ - MAV_COMP_ID_BATTERY2=181, /* Battery #2. | */ - MAV_COMP_ID_MAVCAN=189, /* CAN over MAVLink client. | */ - MAV_COMP_ID_MISSIONPLANNER=190, /* Component that can generate/supply a mission flight plan (e.g. GCS or developer API). | */ - MAV_COMP_ID_ONBOARD_COMPUTER=191, /* Component that lives on the onboard computer (companion computer) and has some generic functionalities, such as settings system parameters and monitoring the status of some processes that don't directly speak mavlink and so on. | */ - MAV_COMP_ID_ONBOARD_COMPUTER2=192, /* Component that lives on the onboard computer (companion computer) and has some generic functionalities, such as settings system parameters and monitoring the status of some processes that don't directly speak mavlink and so on. | */ - MAV_COMP_ID_ONBOARD_COMPUTER3=193, /* Component that lives on the onboard computer (companion computer) and has some generic functionalities, such as settings system parameters and monitoring the status of some processes that don't directly speak mavlink and so on. | */ - MAV_COMP_ID_ONBOARD_COMPUTER4=194, /* Component that lives on the onboard computer (companion computer) and has some generic functionalities, such as settings system parameters and monitoring the status of some processes that don't directly speak mavlink and so on. | */ - MAV_COMP_ID_PATHPLANNER=195, /* Component that finds an optimal path between points based on a certain constraint (e.g. minimum snap, shortest path, cost, etc.). | */ - MAV_COMP_ID_OBSTACLE_AVOIDANCE=196, /* Component that plans a collision free path between two points. | */ - MAV_COMP_ID_VISUAL_INERTIAL_ODOMETRY=197, /* Component that provides position estimates using VIO techniques. | */ - MAV_COMP_ID_PAIRING_MANAGER=198, /* Component that manages pairing of vehicle and GCS. | */ - MAV_COMP_ID_IMU=200, /* Inertial Measurement Unit (IMU) #1. | */ - MAV_COMP_ID_IMU_2=201, /* Inertial Measurement Unit (IMU) #2. | */ - MAV_COMP_ID_IMU_3=202, /* Inertial Measurement Unit (IMU) #3. | */ - MAV_COMP_ID_GPS=220, /* GPS #1. | */ - MAV_COMP_ID_GPS2=221, /* GPS #2. | */ - MAV_COMP_ID_ODID_TXRX_1=236, /* Open Drone ID transmitter/receiver (Bluetooth/WiFi/Internet). | */ - MAV_COMP_ID_ODID_TXRX_2=237, /* Open Drone ID transmitter/receiver (Bluetooth/WiFi/Internet). | */ - MAV_COMP_ID_ODID_TXRX_3=238, /* Open Drone ID transmitter/receiver (Bluetooth/WiFi/Internet). | */ - MAV_COMP_ID_UDP_BRIDGE=240, /* Component to bridge MAVLink to UDP (i.e. from a UART). | */ - MAV_COMP_ID_UART_BRIDGE=241, /* Component to bridge to UART (i.e. from UDP). | */ - MAV_COMP_ID_TUNNEL_NODE=242, /* Component handling TUNNEL messages (e.g. vendor specific GUI of a component). | */ - MAV_COMP_ID_SYSTEM_CONTROL=250, /* Deprecated, don't use. Component for handling system messages (e.g. to ARM, takeoff, etc.). | */ - MAV_COMPONENT_ENUM_END=251, /* | */ -} MAV_COMPONENT; -#endif - -// MAVLINK VERSION - -#ifndef MAVLINK_VERSION -#define MAVLINK_VERSION 3 -#endif - -#if (MAVLINK_VERSION == 0) -#undef MAVLINK_VERSION -#define MAVLINK_VERSION 3 -#endif - -// MESSAGE DEFINITIONS -#include "./mavlink_msg_heartbeat.h" -#include "./mavlink_msg_protocol_version.h" - -// base include - - - -#if MAVLINK_MINIMAL_XML_HASH == MAVLINK_PRIMARY_XML_HASH -# define MAVLINK_MESSAGE_INFO {MAVLINK_MESSAGE_INFO_HEARTBEAT, MAVLINK_MESSAGE_INFO_PROTOCOL_VERSION} -# define MAVLINK_MESSAGE_NAMES {{ "HEARTBEAT", 0 }, { "PROTOCOL_VERSION", 300 }} -# if MAVLINK_COMMAND_24BIT -# include "../mavlink_get_info.h" -# endif -#endif - -#ifdef __cplusplus -} -#endif // __cplusplus -#endif // MAVLINK_MINIMAL_H diff --git a/TelemetryManager/Inc/official_mavlink_2_library/minimal/testsuite.h b/TelemetryManager/Inc/official_mavlink_2_library/minimal/testsuite.h deleted file mode 100644 index ad2471cd..00000000 --- a/TelemetryManager/Inc/official_mavlink_2_library/minimal/testsuite.h +++ /dev/null @@ -1,164 +0,0 @@ -/** @file - * @brief MAVLink comm protocol testsuite generated from minimal.xml - * @see https://mavlink.io/en/ - */ -#pragma once -#ifndef MINIMAL_TESTSUITE_H -#define MINIMAL_TESTSUITE_H - -#ifdef __cplusplus -extern "C" { -#endif - -#ifndef MAVLINK_TEST_ALL -#define MAVLINK_TEST_ALL - -static void mavlink_test_minimal(uint8_t, uint8_t, mavlink_message_t *last_msg); - -static void mavlink_test_all(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg) -{ - - mavlink_test_minimal(system_id, component_id, last_msg); -} -#endif - - - - -static void mavlink_test_heartbeat(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg) -{ -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - mavlink_status_t *status = mavlink_get_channel_status(MAVLINK_COMM_0); - if ((status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_HEARTBEAT >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_heartbeat_t packet_in = { - 963497464,17,84,151,218,3 - }; - mavlink_heartbeat_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.custom_mode = packet_in.custom_mode; - packet1.type = packet_in.type; - packet1.autopilot = packet_in.autopilot; - packet1.base_mode = packet_in.base_mode; - packet1.system_status = packet_in.system_status; - packet1.mavlink_version = packet_in.mavlink_version; - - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_HEARTBEAT_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_HEARTBEAT_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_heartbeat_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_heartbeat_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_heartbeat_pack(system_id, component_id, &msg , packet1.type , packet1.autopilot , packet1.base_mode , packet1.custom_mode , packet1.system_status ); - mavlink_msg_heartbeat_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_heartbeat_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.type , packet1.autopilot , packet1.base_mode , packet1.custom_mode , packet1.system_status ); - mavlink_msg_heartbeat_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_PROTOCOL_VERSION >= 256) { - return; - } -#endif - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_protocol_version_t packet_in = { - 17235,17339,17443,{ 151, 152, 153, 154, 155, 156, 157, 158 },{ 175, 176, 177, 178, 179, 180, 181, 182 } - }; - mavlink_protocol_version_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.version = packet_in.version; - packet1.min_version = packet_in.min_version; - packet1.max_version = packet_in.max_version; - - mav_array_memcpy(packet1.spec_version_hash, packet_in.spec_version_hash, sizeof(uint8_t)*8); - mav_array_memcpy(packet1.library_version_hash, packet_in.library_version_hash, sizeof(uint8_t)*8); - -#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 - if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { - // cope with extensions - memset(MAVLINK_MSG_ID_PROTOCOL_VERSION_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_PROTOCOL_VERSION_MIN_LEN); - } -#endif - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_protocol_version_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_protocol_version_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_protocol_version_pack(system_id, component_id, &msg , packet1.version , packet1.min_version , packet1.max_version , packet1.spec_version_hash , packet1.library_version_hash ); - mavlink_msg_protocol_version_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_protocol_version_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.version , packet1.min_version , packet1.max_version , packet1.spec_version_hash , packet1.library_version_hash ); - mavlink_msg_protocol_version_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; imagic == MAVLINK_STX_MAVLINK1) { - return msg->len + MAVLINK_CORE_HEADER_MAVLINK1_LEN+1 + 2; - } - uint16_t signature_len = (msg->incompat_flags & MAVLINK_IFLAG_SIGNED)?MAVLINK_SIGNATURE_BLOCK_LEN:0; - return msg->len + MAVLINK_NUM_NON_PAYLOAD_BYTES + signature_len; -} - -#if MAVLINK_NEED_BYTE_SWAP -static inline void byte_swap_2(char *dst, const char *src) -{ - dst[0] = src[1]; - dst[1] = src[0]; -} -static inline void byte_swap_4(char *dst, const char *src) -{ - dst[0] = src[3]; - dst[1] = src[2]; - dst[2] = src[1]; - dst[3] = src[0]; -} -static inline void byte_swap_8(char *dst, const char *src) -{ - dst[0] = src[7]; - dst[1] = src[6]; - dst[2] = src[5]; - dst[3] = src[4]; - dst[4] = src[3]; - dst[5] = src[2]; - dst[6] = src[1]; - dst[7] = src[0]; -} -#elif !MAVLINK_ALIGNED_FIELDS -static inline void byte_copy_2(char *dst, const char *src) -{ - dst[0] = src[0]; - dst[1] = src[1]; -} -static inline void byte_copy_4(char *dst, const char *src) -{ - dst[0] = src[0]; - dst[1] = src[1]; - dst[2] = src[2]; - dst[3] = src[3]; -} -static inline void byte_copy_8(char *dst, const char *src) -{ - memcpy(dst, src, 8); -} -#endif - -#define _mav_put_uint8_t(buf, wire_offset, b) buf[wire_offset] = (uint8_t)b -#define _mav_put_int8_t(buf, wire_offset, b) buf[wire_offset] = (int8_t)b -#define _mav_put_char(buf, wire_offset, b) buf[wire_offset] = b - -#if MAVLINK_NEED_BYTE_SWAP -#define _mav_put_uint16_t(buf, wire_offset, b) byte_swap_2(&buf[wire_offset], (const char *)&b) -#define _mav_put_int16_t(buf, wire_offset, b) byte_swap_2(&buf[wire_offset], (const char *)&b) -#define _mav_put_uint32_t(buf, wire_offset, b) byte_swap_4(&buf[wire_offset], (const char *)&b) -#define _mav_put_int32_t(buf, wire_offset, b) byte_swap_4(&buf[wire_offset], (const char *)&b) -#define _mav_put_uint64_t(buf, wire_offset, b) byte_swap_8(&buf[wire_offset], (const char *)&b) -#define _mav_put_int64_t(buf, wire_offset, b) byte_swap_8(&buf[wire_offset], (const char *)&b) -#define _mav_put_float(buf, wire_offset, b) byte_swap_4(&buf[wire_offset], (const char *)&b) -#define _mav_put_double(buf, wire_offset, b) byte_swap_8(&buf[wire_offset], (const char *)&b) -#elif !MAVLINK_ALIGNED_FIELDS -#define _mav_put_uint16_t(buf, wire_offset, b) byte_copy_2(&buf[wire_offset], (const char *)&b) -#define _mav_put_int16_t(buf, wire_offset, b) byte_copy_2(&buf[wire_offset], (const char *)&b) -#define _mav_put_uint32_t(buf, wire_offset, b) byte_copy_4(&buf[wire_offset], (const char *)&b) -#define _mav_put_int32_t(buf, wire_offset, b) byte_copy_4(&buf[wire_offset], (const char *)&b) -#define _mav_put_uint64_t(buf, wire_offset, b) byte_copy_8(&buf[wire_offset], (const char *)&b) -#define _mav_put_int64_t(buf, wire_offset, b) byte_copy_8(&buf[wire_offset], (const char *)&b) -#define _mav_put_float(buf, wire_offset, b) byte_copy_4(&buf[wire_offset], (const char *)&b) -#define _mav_put_double(buf, wire_offset, b) byte_copy_8(&buf[wire_offset], (const char *)&b) -#else -#define _mav_put_uint16_t(buf, wire_offset, b) *(uint16_t *)&buf[wire_offset] = b -#define _mav_put_int16_t(buf, wire_offset, b) *(int16_t *)&buf[wire_offset] = b -#define _mav_put_uint32_t(buf, wire_offset, b) *(uint32_t *)&buf[wire_offset] = b -#define _mav_put_int32_t(buf, wire_offset, b) *(int32_t *)&buf[wire_offset] = b -#define _mav_put_uint64_t(buf, wire_offset, b) *(uint64_t *)&buf[wire_offset] = b -#define _mav_put_int64_t(buf, wire_offset, b) *(int64_t *)&buf[wire_offset] = b -#define _mav_put_float(buf, wire_offset, b) *(float *)&buf[wire_offset] = b -#define _mav_put_double(buf, wire_offset, b) *(double *)&buf[wire_offset] = b -#endif - -/* - like memcpy(), but if src is NULL, do a memset to zero -*/ -static inline void mav_array_memcpy(void *dest, const void *src, size_t n) -{ - if (src == NULL) { - memset(dest, 0, n); - } else { - memcpy(dest, src, n); - } -} - -/* - * Place a char array into a buffer - */ -static inline void _mav_put_char_array(char *buf, uint8_t wire_offset, const char *b, uint8_t array_length) -{ - mav_array_memcpy(&buf[wire_offset], b, array_length); - -} - -/* - * Place a uint8_t array into a buffer - */ -static inline void _mav_put_uint8_t_array(char *buf, uint8_t wire_offset, const uint8_t *b, uint8_t array_length) -{ - mav_array_memcpy(&buf[wire_offset], b, array_length); - -} - -/* - * Place a int8_t array into a buffer - */ -static inline void _mav_put_int8_t_array(char *buf, uint8_t wire_offset, const int8_t *b, uint8_t array_length) -{ - mav_array_memcpy(&buf[wire_offset], b, array_length); - -} - -#if MAVLINK_NEED_BYTE_SWAP -#define _MAV_PUT_ARRAY(TYPE, V) \ -static inline void _mav_put_ ## TYPE ##_array(char *buf, uint8_t wire_offset, const TYPE *b, uint8_t array_length) \ -{ \ - if (b == NULL) { \ - memset(&buf[wire_offset], 0, array_length*sizeof(TYPE)); \ - } else { \ - uint16_t i; \ - for (i=0; i bytesReceived) { + // add the new data to GSC.DMAReceiveBuffer + } + else{ + // discard the new data + //not a great way to handle this, but it's a start + } + + // end of ISR + return; +} \ No newline at end of file diff --git a/TelemetryManager/Src/ManagerCommunication.cpp b/TelemetryManager/Src/ManagerCommunication.cpp new file mode 100644 index 00000000..e69de29b diff --git a/TelemetryManager/Src/MavlinkTranslator.cpp b/TelemetryManager/Src/MavlinkTranslator.cpp new file mode 100644 index 00000000..32731403 --- /dev/null +++ b/TelemetryManager/Src/MavlinkTranslator.cpp @@ -0,0 +1,23 @@ +#include "MavlinkTranslator.hpp" + +MavlinkTranslator::MavlinkTranslator() +{ + // Constructor +} + +MavlinkTranslator::~MavlinkTranslator() +{ + // Destructor +} + +void MavlinkTranslator::bytesToMavlinkMsg(CircularBuffer &rxFromGroundByteQueue) +{ + + // Take bytes in rxFromGroundByteQueue and convert them to Mavlink messages +} + +void MavlinkTranslator::addMavlinkMsgToByteQueue(mavlink_message_t &msg, CircularBuffer &txToGroundByteQueue) +{ + + // Take Mavlink messages in txToGroundByteQueue and convert them to bytes +} \ No newline at end of file diff --git a/TelemetryManager/Src/TelemetryManager.cpp b/TelemetryManager/Src/TelemetryManager.cpp new file mode 100644 index 00000000..0c5996d1 --- /dev/null +++ b/TelemetryManager/Src/TelemetryManager.cpp @@ -0,0 +1,82 @@ +#include "TelemetryManager.hpp" + +/** + * @brief This task is called every 500ms. It is responsible for + * sending the highest priority/routine drone "state" data to the ground station. Data such as + * heartbeat message, altitude, attitude, latitude, longitude... And anything else deemed + * important enough to be transmitted at a regular interval. This is the highest priority + * data in the GSC.highPriorityTransmitBuffer. + * + */ +TelemetryTask* routineDataTransmission; + +TelemetryManager::TelemetryManager() { + this->MT = MavlinkTranslator(); + this->GSC = GroundStationCommunication(); +} + +TelemetryManager::~TelemetryManager() { + // Destructor + teardownTasks(); +} + +/** + * @brief Initialize TM threads and timer interrupts. + * + */ +void TelemetryManager::init() { + // register TM tasks with FreeRTOS + spinUpTasks(); +} + +void TelemetryManager::spinUpTasks() { + routineDataTransmission = + new TelemetryTask("routineDataTransmission", configMINIMAL_STACK_SIZE, tskIDLE_PRIORITY, + *this, [](TelemetryManager& tm) -> void { + auto GSC = tm.GSC; + while (true) { + // START: ingest drone state data and pack bytes into + // GSC.highPriorityTransmitBuffer + + // END: ingest drone state data and pack bytes into + // GSC.highPriorityTransmitBuffer + + // transmit the data via GSC.transmit(); function + GSC.transmit(GSC.highPriorityTransmitBuffer); + + // The interval at which the instructions in the lambda function + // are executed. + vTaskDelay(pdMS_TO_TICKS(500)); // Adjust the delay as necessary + } + }); + +} + +void TelemetryManager::update() { + /* + * @brief the following code up to END is responsible for taking data from other managers and converting + * them to Mavlink bytes, then putting them into GSC.lowPriorityTransmitBuffer. + */ + + // START: fill GSC.lowPriorityTransmitBuffer with data to transmit + + // END: fill GSC.lowPriorityTransmitBuffer with data to transmit + + + + + /* + * the following code up to END is responsible for taking the bytes from the GSC.DMAReceiveBuffer and + * converting them to Mavlink messages/triggering the callbacks associated with each Mavlink + * message. + */ + //START: convert bytes from GSC.DMAReceiveBuffer to Mavlink messages + MT.bytesToMavlinkMsg(GSC.DMAReceiveBuffer); + //END: convert bytes from GSC.DMAReceiveBuffer to Mavlink messages + + + // transmit non routine data via GSC.transmit(); function + GSC.transmit(GSC.lowPriorityTransmitBuffer); +} + +void TelemetryManager::teardownTasks() { delete routineDataTransmission; } diff --git a/TelemetryManager/Src/TelemetryTask.cpp b/TelemetryManager/Src/TelemetryTask.cpp new file mode 100644 index 00000000..34bed4aa --- /dev/null +++ b/TelemetryManager/Src/TelemetryTask.cpp @@ -0,0 +1,18 @@ + +#include "TelemetryTask.hpp" + +TelemetryTask::TelemetryTask(const char *taskName, int stackSize, UBaseType_t uxPriority, TelemetryManager &tm, Callback cbLambda) + : tm(tm), cbLambda(cbLambda), xHandle(nullptr) { + xTaskCreate(&TelemetryTask::TaskTrampoline, taskName, stackSize, this, uxPriority, &xHandle); +} + +void TelemetryTask::TaskTrampoline(void *pvParameters) { + auto* context = static_cast(pvParameters); + context->cbLambda(context->tm); + } + +TelemetryTask::~TelemetryTask() { + if (eTaskGetState(xHandle) != eDeleted) { + vTaskDelete(xHandle); + } +} diff --git a/TelemetryManager/Src/mavlink_decoder.cpp b/TelemetryManager/Src/mavlink_decoder.cpp deleted file mode 100644 index 690d0472..00000000 --- a/TelemetryManager/Src/mavlink_decoder.cpp +++ /dev/null @@ -1,109 +0,0 @@ -// -// Created by Yarema Dzulynsky on 2023-07-10. -// - -#include "../Inc/mavlink_decoder.h" - -long MavlinkDecoder::decodedMessages = 0; - -MavlinkDecoder::MavlinkDecoder() { - /* - Register message types with their decoders and post-decoding callbacks here. This is just a - placeholder. - */ - REGISTER_DECODER(MAVLINK_MSG_ID_ATTITUDE, attitude, [](mavlink_attitude_t &message) { - - }); - - REGISTER_DECODER(MAVLINK_MSG_ID_GLOBAL_POSITION_INT, global_position_int, - [](mavlink_global_position_int_t &message) { - - }); - - REGISTER_DECODER(MAVLINK_MSG_ID_HEARTBEAT, heartbeat, [](mavlink_heartbeat_t &message) { - std::cout << "HEARTBEAT" << std::endl; - std::cout << "type: " << message.type << std::endl; - std::cout << "autopilot: " << message.autopilot << std::endl; - std::cout << "base_mode: " << message.base_mode << std::endl; - std::cout << "custom_mode: " << message.custom_mode << std::endl; - std::cout << "system_status: " << message.system_status << std::endl; - std::cout << "mavlink_version: " << message.mavlink_version << std::endl << std::endl; - }); - - REGISTER_DECODER(MAVLINK_MSG_ID_SYS_STATUS, sys_status, [](mavlink_sys_status_t &message) { - - }); - - REGISTER_DECODER(MAVLINK_MSG_ID_GPS_RAW_INT, gps_raw_int, [](mavlink_gps_raw_int_t &message) { - - }); - - REGISTER_DECODER(MAVLINK_MSG_ID_MISSION_CURRENT, mission_current, - [](mavlink_mission_current_t &message) { - - }); - - REGISTER_DECODER(MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT, nav_controller_output, - [](mavlink_nav_controller_output_t &message) { - - }); - - REGISTER_DECODER(MAVLINK_MSG_ID_RC_CHANNELS, rc_channels, [](mavlink_rc_channels_t &message) { - - }); - - REGISTER_DECODER(MAVLINK_MSG_ID_ALTITUDE, altitude, [](mavlink_altitude_t &message) { - - }); - - REGISTER_DECODER(MAVLINK_MSG_ID_BATTERY_STATUS, battery_status, - [](mavlink_battery_status_t &message) { - - }); -} - -MavlinkDecoder::~MavlinkDecoder() { - // no cleanup needed -} - -void MavlinkDecoder::parseBytesToMavlinkMsgs(uint8_t *buffer, std::size_t bufferSize) { - // Process the bytes in the buffer to construct MAVLink messages - - // MAVLink message structure - mavlink_message_t currentMessage; - - // Status of the MAVLink message decoding process - mavlink_status_t currentMessageDecodingStatus; - - std::size_t currentBufferIndex = 0; // Index to traverse the buffer - - while (currentBufferIndex < bufferSize) { - // Try to parse the current byte and see if it corresponds to a MAVLink message - if (mavlink_parse_char(MAVLINK_COMM_0, buffer[currentBufferIndex], ¤tMessage, - ¤tMessageDecodingStatus)) { - bool isMessageDecoded; - // Attempt to decode the constructed MAVLink message - decodeMsg(currentMessage, isMessageDecoded); - } - currentBufferIndex++; - } -} - -void MavlinkDecoder::decodeMsg(mavlink_message_t &msg, bool &isMessageDecoded) { - // Attempt to decode the MAVLink message using the registered decoding functions - - int messageId = msg.msgid; // Extract message ID - - // Try to find a decoding function for the given message ID - auto it = decodingFunctions.find(messageId); - - if (it != decodingFunctions.end()) { - // Found a decoder: Call it - auto decodingFunctionName = it->second; - decodingFunctionName(msg); - isMessageDecoded = true; - } else { - // Decoder not found: Indicate failure - isMessageDecoded = false; - } -} diff --git a/TelemetryManager/Src/mavlink_encoder.cpp b/TelemetryManager/Src/mavlink_encoder.cpp deleted file mode 100644 index 43eec041..00000000 --- a/TelemetryManager/Src/mavlink_encoder.cpp +++ /dev/null @@ -1,63 +0,0 @@ -// This file was created by Yarema Dzulynsky on 2023-07-24. -#include "../Inc/mavlink_encoder.h" - -// Default constructor for the MavlinkEncoder class. -MavlinkEncoder::MavlinkEncoder() = default; - -/** - * Helper function to pack contents of one buffer into another array. - * - * @param bufferLen Length of buffer to add. - * @param arrayBuffer Target buffer to which data will be added. - * @param arrayIndex Current position/index in the target buffer where data should be added. - * @param bufferToAdd Source buffer containing the data to be packed into the arrayBuffer. - */ -void packIntoArray(size_t bufferLen, uint8_t arrayBuffer[], size_t &arrayIndex, - const uint8_t *bufferToAdd) { - // Copy the contents of bufferToAdd into arrayBuffer, starting at arrayIndex. - for (size_t i = 0; i < bufferLen; i++) { - arrayBuffer[arrayIndex++] = bufferToAdd[i]; - } -} - -size_t MavlinkEncoder::packIntoMavlinkByteArray(IncomingData &data, uint8_t outputBuffer[], size_t maxBufferSize) { - // Temporary buffer to hold MAVLink message before copying it to the output buffer. - uint8_t tempBuffer[MAVLINK_MAX_PACKET_LEN] = {0}; - - // Position/index tracker for the output buffer. - size_t outputIndex = 0; - std::size_t tempSize; - - // Check if any of the global position fields are initialized. - if (data.isLatitudeInitialized || data.isLongitudeInitialized || data.isAltitudeInitialized) { - // Encode the global_position_int message and store its size in tempSize. - tempSize = ENCODE_MESSAGE(global_position_int, 0, data.latitude, data.longitude, data.altitude, 0, - data.vx, data.vy, data.vz, 0)(currentMessage, tempBuffer); - - // Check if adding the message will overflow the outputBuffer. - if(outputIndex + tempSize > maxBufferSize) { - // Handle overflow (this could be extended to return an error, truncate, etc.) - } - - // Copy the encoded message from tempBuffer to outputBuffer. - packIntoArray(tempSize, outputBuffer, outputIndex, tempBuffer); - } - - // Check if any of the attitude fields are initialized. - if (data.isRollInitialized || data.isPitchInitialized || data.isYawInitialized) { - // Encode the attitude message and store its size in tempSize. - tempSize = ENCODE_MESSAGE(attitude, 0, data.roll, data.pitch, data.yaw, 0, 0, 0)( - currentMessage, tempBuffer); - - // Check if adding the message will overflow the outputBuffer. - if(outputIndex + tempSize > maxBufferSize) { - // Handle overflow (this could be extended to return an error, truncate, etc.) - } - - // Copy the encoded message from tempBuffer to outputBuffer. - packIntoArray(tempSize, outputBuffer, outputIndex, tempBuffer); - } - - // Return the actual size of the data that was packed into the outputBuffer. - return outputIndex; -} diff --git a/TelemetryManager/Tests/generic_test.cpp b/TelemetryManager/Tests/generic_test.cpp deleted file mode 100644 index 54b4bfb8..00000000 --- a/TelemetryManager/Tests/generic_test.cpp +++ /dev/null @@ -1,141 +0,0 @@ -#include -// #include -#include "../Inc/incoming_data.h" -#include "../Inc/mavlink_decoder.h" -#include "../Inc/mavlink_encoder.h" - -void fillTestData(IncomingData &data) { - data.latitude = 1; - data.longitude = 2; - data.altitude = 3; - data.isLatitudeInitialized = true; - data.isLongitudeInitialized = true; - data.isAltitudeInitialized = true; - data.roll = 4; - data.pitch = 5; - data.yaw = 6; - data.isRollInitialized = true; - data.isPitchInitialized = true; - data.isYawInitialized = true; - data.vx = 7; - data.vy = 8; - data.vz = 9; - data.isVxInitialized = true; - data.isVyInitialized = true; - data.isVzInitialized = true; -} - - - -TEST(MavlinkEncoderTest, PackIntoMavlinkByteArrayTest) { - MavlinkEncoder encoder; - IncomingData data; - - // Fill data with test values - fillTestData(data); - - uint8_t encoderBuffer[256] = {0}; - size_t encoderBufferSize = sizeof(encoderBuffer); - encoder.packIntoMavlinkByteArray(data, encoderBuffer, encoderBufferSize); - - // Create mavlink messages - mavlink_message_t globalPositionIntMsg, attitudeMsg; - uint8_t globalPositionIntBuffer[MAVLINK_MAX_PACKET_LEN] = {0}; - uint8_t attitudeBuffer[MAVLINK_MAX_PACKET_LEN] = {0}; - - mavlink_msg_global_position_int_pack(0, 0, &globalPositionIntMsg, 0, 1, 2, 3, 0, 7, 8, 9, 0); - size_t globalPositionIntBufferLen = mavlink_msg_to_send_buffer(globalPositionIntBuffer, &globalPositionIntMsg); - - mavlink_msg_attitude_pack(0, 0, &attitudeMsg, 0, 4, 5, 6, 0, 0, 0); - size_t attitudeBufferLen = mavlink_msg_to_send_buffer(attitudeBuffer, &attitudeMsg); - - uint8_t outputBuffer[MAVLINK_MAX_PACKET_LEN * 2] = {0}; - size_t outputIndex = 0; - - memcpy(outputBuffer, globalPositionIntBuffer, globalPositionIntBufferLen); - outputIndex += globalPositionIntBufferLen; - memcpy(outputBuffer + outputIndex, attitudeBuffer, attitudeBufferLen); - outputIndex += attitudeBufferLen; - - int errorCount = 0; - for (size_t i = 0; i < outputIndex; i++) { - if (outputBuffer[i] != encoderBuffer[i]) { - errorCount++; - } - } - - const int amountOfMessages = 2; - ASSERT_TRUE(errorCount <= amountOfMessages * 3) << "There were " << errorCount << " errors in the encoder buffer"; -} - -TEST(MavlinkEncoderDecoderTest, EncodeThenDecodeTest) { - MavlinkEncoder encoder; - IncomingData data; - - // Fill data with test values - fillTestData(data); - - uint8_t encoderBuffer[256] = {0}; - size_t encoderBufferSize = sizeof(encoderBuffer); - encoder.packIntoMavlinkByteArray(data, encoderBuffer, encoderBufferSize); - - MavlinkDecoder decoder; - int expectedNumberOfMessagesDecoded = 2; - - decoder.parseBytesToMavlinkMsgs(encoderBuffer, encoderBufferSize); - ASSERT_EQ(MavlinkDecoder::decodedMessages, expectedNumberOfMessagesDecoded); - - MavlinkDecoder::decodedMessages = 0; -} - -TEST(MavlinkDecoderTest, ParseBytesToMavlinkMsgsTest) { - MavlinkDecoder decoder; - int expectedNumberOfMessagesDecoded = 2; - - - mavlink_message_t globalPositionIntMsg, attitudeMsg; - uint8_t globalPositionIntBuffer[MAVLINK_MAX_PACKET_LEN] = {0}; - uint8_t attitudeBuffer[MAVLINK_MAX_PACKET_LEN] = {0}; - - mavlink_msg_global_position_int_pack(0, 0, &globalPositionIntMsg, 0, 1, 2, 3, 0, 7, 8, 9, 0); - size_t globalPositionIntBufferLen = mavlink_msg_to_send_buffer(globalPositionIntBuffer, &globalPositionIntMsg); - - mavlink_msg_attitude_pack(0, 0, &attitudeMsg, 0, 4, 5, 6, 0, 0, 0); - size_t attitudeBufferLen = mavlink_msg_to_send_buffer(attitudeBuffer, &attitudeMsg); - - uint8_t outputBuffer[MAVLINK_MAX_PACKET_LEN * 2] = {0}; - - memcpy(outputBuffer, globalPositionIntBuffer, globalPositionIntBufferLen); - - memcpy(outputBuffer + globalPositionIntBufferLen, attitudeBuffer, attitudeBufferLen); - - - decoder.parseBytesToMavlinkMsgs(outputBuffer, globalPositionIntBufferLen + attitudeBufferLen); - - ASSERT_EQ(MavlinkDecoder::decodedMessages, expectedNumberOfMessagesDecoded); - - MavlinkDecoder::decodedMessages = 0; -} - -TEST(EncoderMacroTest, global_position_int) { - uint8_t buffer[256]; - - // Use the ENCODE_MESSAGE macro to encode - mavlink_message_t msg; - ENCODE_MESSAGE(global_position_int, 1, 2, 3, 4, 5, 6, 7, 8, 9)(msg, buffer); - - // Decode the message - mavlink_global_position_int_t globalPositionInt; - mavlink_msg_global_position_int_decode(&msg, &globalPositionInt); - - // Assertions - ASSERT_EQ(globalPositionInt.time_boot_ms, 1); - ASSERT_EQ(globalPositionInt.lat, 2); - ASSERT_EQ(globalPositionInt.lon, 3); - ASSERT_EQ(globalPositionInt.alt, 4); - ASSERT_EQ(globalPositionInt.relative_alt, 5); - ASSERT_EQ(globalPositionInt.vx, 6); - ASSERT_EQ(globalPositionInt.vy, 7); - ASSERT_EQ(globalPositionInt.vz, 8); - ASSERT_EQ(globalPositionInt.hdg, 9); -} diff --git a/TelemetryManager/Tests/temp.txt b/TelemetryManager/Tests/temp.txt new file mode 100644 index 00000000..e69de29b diff --git a/Tools/Testing/CMakeLists.txt b/Tools/Testing/CMakeLists.txt index 38243e32..6d00eeb9 100644 --- a/Tools/Testing/CMakeLists.txt +++ b/Tools/Testing/CMakeLists.txt @@ -76,7 +76,7 @@ file(GLOB TM_CODE "${TM_FOLDER}/Tests/generic_test.cpp" # add necessary TelemetryManager source files below - "${TM_SRC}/*.cpp" + # "${TM_SRC}/*.cpp" ) # Drivers From f1d175259256043e52c9093899ab97f256b05674 Mon Sep 17 00:00:00 2001 From: Alyzen Jeraj <38901318+alyzenjeraj@users.noreply.github.com> Date: Fri, 5 Apr 2024 11:11:44 -0400 Subject: [PATCH 04/15] Am/fbwa (#42) Co-authored-by: Anthony Luo --- AttitudeManager/FlightModes/Inc/fbwa.hpp | 24 +++++++++ .../FlightModes/Inc/flightmode.hpp | 2 + AttitudeManager/FlightModes/Inc/manual.hpp | 2 + AttitudeManager/FlightModes/Src/fbwa.cpp | 51 +++++++++++++++++++ AttitudeManager/FlightModes/Src/manual.cpp | 2 + AttitudeManager/Inc/AM.hpp | 5 ++ Common/Inc/CommonDataTypes.hpp | 15 ++++++ Config_Models/config_foundation.hpp | 13 ----- .../example_model/{config.hpp => model.hpp} | 17 +++++-- Drivers/MotorChannel/Inc/ZP_D_PWMChannel.hpp | 2 +- Testing/Mocks/Inc/MockFlightmode.hpp | 2 + Tools/Testing/CMakeLists.txt | 2 +- 12 files changed, 118 insertions(+), 19 deletions(-) create mode 100644 AttitudeManager/FlightModes/Inc/fbwa.hpp create mode 100644 AttitudeManager/FlightModes/Src/fbwa.cpp rename Config_Models/example_model/{config.hpp => model.hpp} (89%) diff --git a/AttitudeManager/FlightModes/Inc/fbwa.hpp b/AttitudeManager/FlightModes/Inc/fbwa.hpp new file mode 100644 index 00000000..ea694000 --- /dev/null +++ b/AttitudeManager/FlightModes/Inc/fbwa.hpp @@ -0,0 +1,24 @@ +#ifndef ZPSW3_AM_FBWA_HPP +#define ZPSW3_AM_FBWA_HPP + +#include "flightmode.hpp" + +namespace AM { + +class FBWA : public Flightmode { + public: + FBWA() = default; + + AttitudeManagerInput run(const AttitudeManagerInput& input) override; + void updatePid() override; + void updatePidGains() override; + void updateControlLimits(ControlLimits_t limits) override; + + private: + // TODO: FIXME to be a control limit class + ControlLimits_t fbwa_control_limits; +}; + +} // namespace AM + +#endif // ZPSW3_AM_FBWA_HPP diff --git a/AttitudeManager/FlightModes/Inc/flightmode.hpp b/AttitudeManager/FlightModes/Inc/flightmode.hpp index f62902d8..e909e637 100644 --- a/AttitudeManager/FlightModes/Inc/flightmode.hpp +++ b/AttitudeManager/FlightModes/Inc/flightmode.hpp @@ -19,6 +19,8 @@ class Flightmode { virtual AttitudeManagerInput run(const AttitudeManagerInput& input) = 0; virtual void updatePid() = 0; + virtual void updatePidGains() = 0; + virtual void updateControlLimits(ControlLimits_t limits) = 0; protected: Flightmode() = default; diff --git a/AttitudeManager/FlightModes/Inc/manual.hpp b/AttitudeManager/FlightModes/Inc/manual.hpp index be4338e2..001c3e13 100644 --- a/AttitudeManager/FlightModes/Inc/manual.hpp +++ b/AttitudeManager/FlightModes/Inc/manual.hpp @@ -11,6 +11,8 @@ class Manual : public Flightmode { AttitudeManagerInput run(const AttitudeManagerInput& input) override; void updatePid() override; + void updatePidGains() override; + void updateControlLimits(ControlLimits_t limits) override; }; } // namespace AM diff --git a/AttitudeManager/FlightModes/Src/fbwa.cpp b/AttitudeManager/FlightModes/Src/fbwa.cpp new file mode 100644 index 00000000..f78b5ad8 --- /dev/null +++ b/AttitudeManager/FlightModes/Src/fbwa.cpp @@ -0,0 +1,51 @@ +#include "fbwa.hpp" +#include "CommonDataTypes.hpp" +#include "AM.hpp" +#include + +namespace AM { + AttitudeManagerInput FBWA::run(const AttitudeManagerInput& input) { + + AttitudeManagerInput mappedOutputs; + + // TODO: bound checking that doesn't throw an abort() and program exit + // Bounded checking to make sure input is within max and min + // assert(input.pitch <= AM::AttitudeManager::INPUT_MAX && input.pitch >= AM::AttitudeManager::INPUT_MIN); + // assert(input.roll <= AM::AttitudeManager::INPUT_MAX && input.roll >= AM::AttitudeManager::INPUT_MIN); + // assert(input.yaw <= AM::AttitudeManager::INPUT_MAX && input.yaw >= AM::AttitudeManager::INPUT_MIN); + // assert(input.throttle <= AM::AttitudeManager::INPUT_MAX && input.throttle >= AM::AttitudeManager::INPUT_MIN); + + // Mapping inputs to outputs with ratios of min-max + // Mapping maintains 0->0 I/O + mappedOutputs.pitch = + input.pitch < 0 + ? input.pitch * (fbwa_control_limits.pitchLimit.min / AM::AttitudeManager::INPUT_MIN) + : input.pitch * (fbwa_control_limits.pitchLimit.max / AM::AttitudeManager::INPUT_MAX); + mappedOutputs.roll = + input.roll < 0 + ? input.roll * (fbwa_control_limits.rollLimit.min / AM::AttitudeManager::INPUT_MIN) + : input.roll * (fbwa_control_limits.rollLimit.max / AM::AttitudeManager::INPUT_MAX); + mappedOutputs.yaw = + input.yaw < 0 + ? input.yaw * (fbwa_control_limits.yawLimit.min / AM::AttitudeManager::INPUT_MIN) + : input.yaw * (fbwa_control_limits.yawLimit.max / AM::AttitudeManager::INPUT_MAX); + + // Throttle maps -100-100 to range 0-100 + mappedOutputs.throttle = + fbwa_control_limits.throttleLimit.min + + (input.throttle - AM::AttitudeManager::INPUT_MIN) * + (fbwa_control_limits.throttleLimit.max - fbwa_control_limits.throttleLimit.min) / + (AM::AttitudeManager::INPUT_MAX - AM::AttitudeManager::INPUT_MIN); + + return mappedOutputs; + } + + void FBWA::updatePid() {} //Needs to be implemented + + void FBWA::updatePidGains() {} //Needs to be implemented + + void FBWA::updateControlLimits(ControlLimits_t limits) { + // TODO: make this better than a straight copy + fbwa_control_limits = limits; + } +} \ No newline at end of file diff --git a/AttitudeManager/FlightModes/Src/manual.cpp b/AttitudeManager/FlightModes/Src/manual.cpp index 0b80e325..7b258380 100644 --- a/AttitudeManager/FlightModes/Src/manual.cpp +++ b/AttitudeManager/FlightModes/Src/manual.cpp @@ -8,5 +8,7 @@ AttitudeManagerInput Manual::run(const AttitudeManagerInput& input) { } void Manual::updatePid() {} +void Manual::updatePidGains() {} +void Manual::updateControlLimits(ControlLimits_t limits) {} } // namespace AM diff --git a/AttitudeManager/Inc/AM.hpp b/AttitudeManager/Inc/AM.hpp index 559d7b1b..9019b5da 100644 --- a/AttitudeManager/Inc/AM.hpp +++ b/AttitudeManager/Inc/AM.hpp @@ -27,6 +27,11 @@ typedef struct { class AttitudeManager { public: + + //Constants used for mapping values + static constexpr float INPUT_MAX = 100; + static constexpr float INPUT_MIN = -100; + static void setControlInputs(const AttitudeManagerInput& new_control_inputs); static AttitudeManagerInput getControlInputs(); diff --git a/Common/Inc/CommonDataTypes.hpp b/Common/Inc/CommonDataTypes.hpp index 5afb6577..020c6559 100644 --- a/Common/Inc/CommonDataTypes.hpp +++ b/Common/Inc/CommonDataTypes.hpp @@ -25,4 +25,19 @@ typedef enum { throttle, NUM_CONTROL_AXIS } ControlAxis_t; + +using percentage_t = float; + +typedef struct AxisLimits_t { + percentage_t min; + percentage_t max; +} AxisLimits_t; + +typedef struct ControlLimits_t { + AxisLimits_t yawLimit; + AxisLimits_t pitchLimit; + AxisLimits_t rollLimit; + AxisLimits_t throttleLimit; +} ControlLimits_t; + #endif // ZPSW3_COMMON_DATATYPES_HPP diff --git a/Config_Models/config_foundation.hpp b/Config_Models/config_foundation.hpp index 6b2cdd91..90040c05 100644 --- a/Config_Models/config_foundation.hpp +++ b/Config_Models/config_foundation.hpp @@ -9,7 +9,6 @@ namespace config { - using percentage_t = float; //Define factory function to create drivers and flightmodes template @@ -65,18 +64,6 @@ namespace config AxisPID_t throttlePID = {}; } ControlPID_t; - typedef struct { - percentage_t min = 0.0f; - percentage_t max = 100.0f; - } AxisLimits_t; - - typedef struct { - AxisLimits_t yawLimit = {}; - AxisLimits_t pitchLimit = {}; - AxisLimits_t rollLimit = {}; - AxisLimits_t throttleLimit = {}; - } ControlLimits_t; - typedef struct { ControlPID_t PIDValues = {}; ControlLimits_t controlLimits = {}; diff --git a/Config_Models/example_model/config.hpp b/Config_Models/example_model/model.hpp similarity index 89% rename from Config_Models/example_model/config.hpp rename to Config_Models/example_model/model.hpp index 7c03e407..8213f5b7 100644 --- a/Config_Models/example_model/config.hpp +++ b/Config_Models/example_model/model.hpp @@ -2,9 +2,10 @@ #define ZPSW3_CONFIG_HPP #include "config_foundation.hpp" -#include "ZP_D_PWMChannel.hpp" #include "manual.hpp" +#include "fbwa.hpp" #include "tim.h" +#include "ZP_D_PWMChannel.hpp" namespace config { @@ -81,7 +82,7 @@ namespace config } } }, - .flightmodeConstructor = constructObject + .flightmodeConstructor = constructObject }, { //Flightmode2 .tuningData{ @@ -101,16 +102,24 @@ namespace config }, .controlLimits = { .yawLimit = { - .min = 5.0f, + .min = -95.0f, .max = 95.0f }, + .pitchLimit = { + .min = -30.0f, + .max = 30.0f + }, .rollLimit = { + .min = -100.0f, + .max = 100.0f + }, + .throttleLimit = { .min = 0.0f, .max = 100.0f } } }, - .flightmodeConstructor = constructObject + .flightmodeConstructor = constructObject } }; diff --git a/Drivers/MotorChannel/Inc/ZP_D_PWMChannel.hpp b/Drivers/MotorChannel/Inc/ZP_D_PWMChannel.hpp index 555043b6..7697e5bc 100644 --- a/Drivers/MotorChannel/Inc/ZP_D_PWMChannel.hpp +++ b/Drivers/MotorChannel/Inc/ZP_D_PWMChannel.hpp @@ -1,7 +1,7 @@ #ifndef ZP_D_PWM_CHANNEL_HPP_ #define ZP_D_PWM_CHANNEL_HPP_ -#include "main.h" +#include "tim.h" #include "ZP_D_MotorChannel.hpp" diff --git a/Testing/Mocks/Inc/MockFlightmode.hpp b/Testing/Mocks/Inc/MockFlightmode.hpp index d70d542a..32ea0255 100644 --- a/Testing/Mocks/Inc/MockFlightmode.hpp +++ b/Testing/Mocks/Inc/MockFlightmode.hpp @@ -7,4 +7,6 @@ class MockFlightmode : public AM::Flightmode{ return input; }; void updatePid(){}; + void updatePidGains() {}; + void updateControlLimits(ControlLimits_t limits) {}; }; \ No newline at end of file diff --git a/Tools/Testing/CMakeLists.txt b/Tools/Testing/CMakeLists.txt index 6d00eeb9..ad512dac 100644 --- a/Tools/Testing/CMakeLists.txt +++ b/Tools/Testing/CMakeLists.txt @@ -125,7 +125,7 @@ file(GLOB STUBS_CODE ) #Models -include_directories("${ROOT_DIR}/Config_Models") +include_directories(${ROOT_DIR}/Config_Models) file(GLOB MODELS_CODE ) From 186cfb0ebd21856970c1e081ea1c4a72ae630b62 Mon Sep 17 00:00:00 2001 From: Derek Tang <68519418+DerekTang04@users.noreply.github.com> Date: Mon, 13 May 2024 18:54:12 -0400 Subject: [PATCH 05/15] Reformatting drivers folder (#51) Co-authored-by: ydzulynsky --- Drivers/Common/Inc/circular_buffer.hpp | 66 ----------------- Drivers/Common/Src/drivers_config.cpp | 10 --- Drivers/UARTDevice/Src/uart_device.cpp | 42 ----------- .../circular_buffer/inc/circular_buffer.hpp | 72 +++++++++++++++++++ .../circular_buffer/src}/circular_buffer.cpp | 14 ++-- .../dma_uart_device/inc/dma_uart_device.hpp} | 18 +++-- .../dma_uart_device/src/dma_uart_device.cpp | 39 ++++++++++ .../Src => common}/drivers_callbacks.cpp | 2 +- .../drivers_config/inc}/drivers_config.hpp | 4 +- .../drivers_config/src/drivers_config.cpp | 19 +++++ .../inc}/independent_watchdog.h | 1 + .../Inc => iwdg_driver/inc}/watchdog.h | 4 +- .../src}/independent_watchdog.cpp | 1 + .../inc}/ZP_D_MotorChannel.hpp | 0 .../inc}/ZP_D_PWMChannel.hpp | 0 .../src}/ZP_D_PWMChannel.cpp | 0 .../{Inc => inc}/rcreceiver_datatypes.h | 0 .../rc_receiver/{Inc => inc}/sbus_defines.h | 0 .../{Inc => inc}/sbus_receiver.hpp | 0 .../{Src => src}/sbus_receiver.cpp | 0 .../ccontrol/inc}/ccontrol_functions.h | 0 .../Src => sensor_fusion/ccontrol/src}/inv.c | 0 .../Src => sensor_fusion/ccontrol/src}/lup.c | 0 .../Src => sensor_fusion/ccontrol/src}/mul.c | 0 .../Src => sensor_fusion/ccontrol/src}/tran.c | 0 .../{Inc => inc}/common_data_types.hpp | 0 .../sensor_fusion/{Inc => inc}/manhony_ahrs.h | 0 .../{Inc => inc}/math_constants.hpp | 0 .../{Inc => inc}/sensor_fusion.hpp | 0 .../{Inc => inc}/sensor_fusion_interface.hpp | 0 .../sensor_fusion/{Inc => inc}/sf_config.h | 0 .../{Src => src}/manhony_ahrs.cpp | 0 .../{Src => src}/sensor_fusion.cpp | 0 .../{Src => src}/sensor_fusion_interface.cpp | 0 .../{Tests => tests}/CircularBufferTest.cpp | 0 .../Inc/GroundStationCommunication.hpp | 32 ++++++--- TelemetryManager/Inc/MavlinkTranslator.hpp | 6 +- ...ircularBuffer.hpp => TMCircularBuffer.hpp} | 47 ++++++------ TelemetryManager/Src/CircularBuffer.cpp | 28 -------- .../Src/GroundStationCommunication.cpp | 23 +++--- TelemetryManager/Src/MavlinkTranslator.cpp | 4 +- TelemetryManager/Src/TMCircularBuffer.cpp | 30 ++++++++ Tools/Firmware/CMakeLists.txt | 38 +++++----- Tools/Testing/CMakeLists.txt | 26 ++++--- 44 files changed, 290 insertions(+), 236 deletions(-) delete mode 100644 Drivers/Common/Inc/circular_buffer.hpp delete mode 100644 Drivers/Common/Src/drivers_config.cpp delete mode 100644 Drivers/UARTDevice/Src/uart_device.cpp create mode 100644 Drivers/common/circular_buffer/inc/circular_buffer.hpp rename Drivers/{Common/Src => common/circular_buffer/src}/circular_buffer.cpp (86%) rename Drivers/{UARTDevice/Inc/uart_device.hpp => common/dma_uart_device/inc/dma_uart_device.hpp} (87%) create mode 100644 Drivers/common/dma_uart_device/src/dma_uart_device.cpp rename Drivers/{Common/Src => common}/drivers_callbacks.cpp (94%) rename Drivers/{Common/Inc => common/drivers_config/inc}/drivers_config.hpp (77%) create mode 100644 Drivers/common/drivers_config/src/drivers_config.cpp rename Drivers/{IWDG_Driver/Inc => iwdg_driver/inc}/independent_watchdog.h (99%) rename Drivers/{IWDG_Driver/Inc => iwdg_driver/inc}/watchdog.h (91%) rename Drivers/{IWDG_Driver/Src => iwdg_driver/src}/independent_watchdog.cpp (99%) rename Drivers/{MotorChannel/Inc => motor_channel/inc}/ZP_D_MotorChannel.hpp (100%) rename Drivers/{MotorChannel/Inc => motor_channel/inc}/ZP_D_PWMChannel.hpp (100%) rename Drivers/{MotorChannel/Src => motor_channel/src}/ZP_D_PWMChannel.cpp (100%) rename Drivers/rc_receiver/{Inc => inc}/rcreceiver_datatypes.h (100%) rename Drivers/rc_receiver/{Inc => inc}/sbus_defines.h (100%) rename Drivers/rc_receiver/{Inc => inc}/sbus_receiver.hpp (100%) rename Drivers/rc_receiver/{Src => src}/sbus_receiver.cpp (100%) rename Drivers/{ccontrol/Inc => sensor_fusion/ccontrol/inc}/ccontrol_functions.h (100%) rename Drivers/{ccontrol/Src => sensor_fusion/ccontrol/src}/inv.c (100%) rename Drivers/{ccontrol/Src => sensor_fusion/ccontrol/src}/lup.c (100%) rename Drivers/{ccontrol/Src => sensor_fusion/ccontrol/src}/mul.c (100%) rename Drivers/{ccontrol/Src => sensor_fusion/ccontrol/src}/tran.c (100%) rename Drivers/sensor_fusion/{Inc => inc}/common_data_types.hpp (100%) rename Drivers/sensor_fusion/{Inc => inc}/manhony_ahrs.h (100%) rename Drivers/sensor_fusion/{Inc => inc}/math_constants.hpp (100%) rename Drivers/sensor_fusion/{Inc => inc}/sensor_fusion.hpp (100%) rename Drivers/sensor_fusion/{Inc => inc}/sensor_fusion_interface.hpp (100%) rename Drivers/sensor_fusion/{Inc => inc}/sf_config.h (100%) rename Drivers/sensor_fusion/{Src => src}/manhony_ahrs.cpp (100%) rename Drivers/sensor_fusion/{Src => src}/sensor_fusion.cpp (100%) rename Drivers/sensor_fusion/{Src => src}/sensor_fusion_interface.cpp (100%) rename Drivers/{Tests => tests}/CircularBufferTest.cpp (100%) rename TelemetryManager/Inc/{CircularBuffer.hpp => TMCircularBuffer.hpp} (65%) delete mode 100644 TelemetryManager/Src/CircularBuffer.cpp create mode 100644 TelemetryManager/Src/TMCircularBuffer.cpp diff --git a/Drivers/Common/Inc/circular_buffer.hpp b/Drivers/Common/Inc/circular_buffer.hpp deleted file mode 100644 index 2d24be72..00000000 --- a/Drivers/Common/Inc/circular_buffer.hpp +++ /dev/null @@ -1,66 +0,0 @@ -#ifndef CIRCULAR_BUFFER_HPP -#define CIRCULAR_BUFFER_HPP - -#include - -class CircularBuffer { - public: - /** @brief Constructor for the CircularBuffer class - * - * CircularBuffer will manage a stack-allocated byte array as a - * circular buffer. - * - * @param buf The byte array to be managed. - * @param size Size of the byte array. This will be the size of - * the circular buffer. - */ - CircularBuffer(uint8_t* buf, uint16_t size); - - /** @brief Read the value of a byte in the circular buffer - * without incrementing the read pointer - * - * @param res The byte value to be returned. Passed by reference. - * @param index The index of the byte. - * @return False if the index is out of bounds. - */ - bool peek(uint8_t& res, uint16_t index); - - /** @brief Read bytes from the circular buffer and increment the - * read pointer. - * - * @param buf The buffer to read the bytes into. - * @param dist Number of bytes to be read. - * @return False if the number of bytes to be read exceed - * the number of available bytes. - */ - bool read(uint8_t* buf, uint16_t dist); - - /** @brief Write a byte into the circular buffer and increment - * the write pointer. - * - * @param byte The byte to write. - * @return False if the circular buffer is already full. - */ - bool write(uint8_t byte); - - /** @brief Check if the circular buffer is full. - * - * @return True if the circular buffer is full. - */ - bool isFull(); - - /** @brief Check the number of bytes available to be read. - * - * @return The number of bytes available to be read. - */ - uint16_t getNumAvailBytes(); - - private: - uint8_t* buf_; - uint16_t size_; - uint16_t writePtr_ = 0; - uint16_t readPtr_ = 0; -}; - - -#endif \ No newline at end of file diff --git a/Drivers/Common/Src/drivers_config.cpp b/Drivers/Common/Src/drivers_config.cpp deleted file mode 100644 index 64eabe6c..00000000 --- a/Drivers/Common/Src/drivers_config.cpp +++ /dev/null @@ -1,10 +0,0 @@ -#include "drivers_config.hpp" - -/* - creating sbusReceiver instance -*/ -SBUSReceiver sbus_instance(sbus_uart); -SBUSReceiver* sbus_pointer = &sbus_instance; - -UARTDevice rfd900Instance(RFD900_UART); -UARTDevice* pRFD900 = &rfd900Instance; diff --git a/Drivers/UARTDevice/Src/uart_device.cpp b/Drivers/UARTDevice/Src/uart_device.cpp deleted file mode 100644 index 95246d1a..00000000 --- a/Drivers/UARTDevice/Src/uart_device.cpp +++ /dev/null @@ -1,42 +0,0 @@ -#include "uart_device.hpp" -#include "main.h" - -UARTDevice::UARTDevice(UART_HandleTypeDef* huart) - : - uart_handle_(huart), circular_buf_(buf_, BUFFER_SIZE) {} - -void UARTDevice::init() { - HAL_UARTEx_ReceiveToIdle_DMA(uart_handle_, it_recv_buf_, BUFFER_SIZE); - __HAL_DMA_DISABLE_IT(uart_handle_->hdmarx, DMA_IT_HT); -} - -void UARTDevice::callback(uint16_t data_size) { - HAL_UARTEx_ReceiveToIdle_DMA(uart_handle_, it_recv_buf_, BUFFER_SIZE); - __HAL_DMA_DISABLE_IT(uart_handle_->hdmarx, DMA_IT_HT); - - for (uint16_t i = 0; i < data_size; ++i) { - circular_buf_.write(it_recv_buf_[i]); - } -} - -bool UARTDevice::matchUART(UART_HandleTypeDef* huart) { - bool match = false; - - if(uart_handle_ != NULL && huart != NULL) { - match = (uart_handle_ == huart); - } - - return match; -} - -void UARTDevice::transmit(uint8_t* buf, uint16_t size) { - HAL_UART_Transmit(uart_handle_, buf, size, TRANSMIT_TIMEOUT); -} - -uint16_t UARTDevice::getAvailDataSize() { - return circular_buf_.getNumAvailBytes(); -} - -bool UARTDevice::read(uint8_t* buf, uint16_t size) { - return circular_buf_.read(buf, size); -} \ No newline at end of file diff --git a/Drivers/common/circular_buffer/inc/circular_buffer.hpp b/Drivers/common/circular_buffer/inc/circular_buffer.hpp new file mode 100644 index 00000000..7af72c95 --- /dev/null +++ b/Drivers/common/circular_buffer/inc/circular_buffer.hpp @@ -0,0 +1,72 @@ +#ifndef CIRCULAR_BUFFER_HPP +#define CIRCULAR_BUFFER_HPP + +#include + +class CircularBuffer { + public: + /** @brief Constructor for the CircularBuffer class + * + * CircularBuffer will manage a stack-allocated byte array as a + * circular buffer. + * + * @param buf The byte array to be managed. + * @param size Size of the byte array. This will be the size of + * the circular buffer. + */ + CircularBuffer(uint8_t* buf, uint16_t size); + + /** @brief Read the value of a byte in the circular buffer + * without incrementing the read pointer + * + * @param res The byte value to be returned. Passed by reference. + * @param index The index of the byte. + * @return False if the index is out of bounds. + */ + bool peek(uint8_t& res, uint16_t index); + + /** @brief Read bytes from the circular buffer and increment the + * read pointer. + * + * @param buf The buffer to read the bytes into. + * @param dist Number of bytes to be read. + * @return False if the number of bytes to be read exceed + * the number of available bytes. + */ + bool read(uint8_t* buf, uint16_t dist); + + /** @brief Write a byte into the circular buffer and increment + * the write pointer. + * + * @param byte The byte to write. + * @return False if the circular buffer is already full. + */ + bool write(uint8_t byte); + + /** @brief Check if the circular buffer is full. + * + * @return True if the circular buffer is full. + */ + bool isFull(); + + /** @brief Check the number of bytes available to be read. + * + * @return The number of bytes available to be read. + */ + uint16_t getNumAvailBytes(); + + /** + * @brief Provide the remaining space in the buffer. + * + * @return uint16_t The remaining space in the buffer. + */ + uint16_t getFreeSpaceBytes(); + + private: + uint8_t* buf_; + uint16_t size_; + uint16_t writePtr_ = 0; + uint16_t readPtr_ = 0; +}; + +#endif \ No newline at end of file diff --git a/Drivers/Common/Src/circular_buffer.cpp b/Drivers/common/circular_buffer/src/circular_buffer.cpp similarity index 86% rename from Drivers/Common/Src/circular_buffer.cpp rename to Drivers/common/circular_buffer/src/circular_buffer.cpp index 3738bf77..299388fa 100644 --- a/Drivers/Common/Src/circular_buffer.cpp +++ b/Drivers/common/circular_buffer/src/circular_buffer.cpp @@ -1,4 +1,5 @@ #include "circular_buffer.hpp" + #include CircularBuffer::CircularBuffer(uint8_t* buf, uint16_t size) { @@ -48,13 +49,10 @@ bool CircularBuffer::isFull() { // The buffer is full when the writePtr_ wraps around to the // readPtr_, so it's ahead of the readPtr_ by value, but overlaps // the readPtr_ by index aftering modding by the buffer size_. - return (writePtr_ != readPtr_) && - (writePtr_ % size_ == readPtr_ % size_); + return (writePtr_ != readPtr_) && (writePtr_ % size_ == readPtr_ % size_); } -uint16_t CircularBuffer::getNumAvailBytes() { - return writePtr_ - readPtr_; -} +uint16_t CircularBuffer::getNumAvailBytes() { return writePtr_ - readPtr_; } bool CircularBuffer::write(uint8_t byte) { bool success = true; @@ -67,4 +65,8 @@ bool CircularBuffer::write(uint8_t byte) { } return success; -} \ No newline at end of file +} + +uint16_t CircularBuffer::getFreeSpaceBytes() { + //NOT IMPLEMENTED YET + return -1; } \ No newline at end of file diff --git a/Drivers/UARTDevice/Inc/uart_device.hpp b/Drivers/common/dma_uart_device/inc/dma_uart_device.hpp similarity index 87% rename from Drivers/UARTDevice/Inc/uart_device.hpp rename to Drivers/common/dma_uart_device/inc/dma_uart_device.hpp index 76a84eb5..95d56ba6 100644 --- a/Drivers/UARTDevice/Inc/uart_device.hpp +++ b/Drivers/common/dma_uart_device/inc/dma_uart_device.hpp @@ -1,5 +1,5 @@ -#ifndef UART_DEVICE_HPP -#define UART_DEVICE_HPP +#ifndef DMA_UART_DEVICE_HPP +#define DMA_UART_DEVICE_HPP #include #include "usart.h" @@ -8,7 +8,7 @@ class UARTDevice { public: /* Size of the internal buffer */ - static const uint16_t BUFFER_SIZE = 280; + static const uint16_t IT_RECV_BUF_SIZE = 280; /** @brief Constructor for the UARTDevice driver. * @@ -16,8 +16,9 @@ class UARTDevice { * data via a specified HAL UART handle. * * @param huart The HAL UART handle to be managed. + * @param buf_ The circular buffer to store received data. */ - UARTDevice(UART_HandleTypeDef* huart); + UARTDevice(UART_HandleTypeDef* huart, CircularBuffer *buf_); /** @brief Initialize the driver. * @@ -77,9 +78,12 @@ class UARTDevice { private: static const uint16_t TRANSMIT_TIMEOUT = 1000; UART_HandleTypeDef* uart_handle_; - uint8_t buf_[BUFFER_SIZE]; - CircularBuffer circular_buf_; - uint8_t it_recv_buf_[BUFFER_SIZE]; + CircularBuffer *circular_buf_; + uint8_t it_recv_buf_[IT_RECV_BUF_SIZE]; + + + + }; #endif \ No newline at end of file diff --git a/Drivers/common/dma_uart_device/src/dma_uart_device.cpp b/Drivers/common/dma_uart_device/src/dma_uart_device.cpp new file mode 100644 index 00000000..c287fcef --- /dev/null +++ b/Drivers/common/dma_uart_device/src/dma_uart_device.cpp @@ -0,0 +1,39 @@ +#include "dma_uart_device.hpp" + +#include "main.h" + +UARTDevice::UARTDevice(UART_HandleTypeDef* huart, CircularBuffer* buf_) : uart_handle_(huart) { + circular_buf_ = buf_; +} + +void UARTDevice::init() { + HAL_UARTEx_ReceiveToIdle_DMA(uart_handle_, it_recv_buf_, IT_RECV_BUF_SIZE); + __HAL_DMA_DISABLE_IT(uart_handle_->hdmarx, DMA_IT_HT); +} + +void UARTDevice::callback(uint16_t data_size) { + HAL_UARTEx_ReceiveToIdle_DMA(uart_handle_, it_recv_buf_, IT_RECV_BUF_SIZE); + __HAL_DMA_DISABLE_IT(uart_handle_->hdmarx, DMA_IT_HT); + + for (uint16_t i = 0; i < data_size; ++i) { + circular_buf_->write(it_recv_buf_[i]); + } +} + +bool UARTDevice::matchUART(UART_HandleTypeDef* huart) { + bool match = false; + + if (uart_handle_ != NULL && huart != NULL) { + match = (uart_handle_ == huart); + } + + return match; +} + +void UARTDevice::transmit(uint8_t* buf, uint16_t size) { + HAL_UART_Transmit(uart_handle_, buf, size, TRANSMIT_TIMEOUT); +} + +uint16_t UARTDevice::getAvailDataSize() { return circular_buf_->getNumAvailBytes(); } + +bool UARTDevice::read(uint8_t* buf, uint16_t size) { return circular_buf_->read(buf, size); } \ No newline at end of file diff --git a/Drivers/Common/Src/drivers_callbacks.cpp b/Drivers/common/drivers_callbacks.cpp similarity index 94% rename from Drivers/Common/Src/drivers_callbacks.cpp rename to Drivers/common/drivers_callbacks.cpp index 2e227b1e..c3434e6a 100644 --- a/Drivers/Common/Src/drivers_callbacks.cpp +++ b/Drivers/common/drivers_callbacks.cpp @@ -35,6 +35,6 @@ void HAL_UART_ErrorCallback(UART_HandleTypeDef *huart) if(pRFD900->matchUART(huart)){ // Clear error and receive data HAL_UART_DMAStop(huart); - pRFD900->callback(UARTDevice::BUFFER_SIZE); + pRFD900->callback(UARTDevice::IT_RECV_BUF_SIZE); } } diff --git a/Drivers/Common/Inc/drivers_config.hpp b/Drivers/common/drivers_config/inc/drivers_config.hpp similarity index 77% rename from Drivers/Common/Inc/drivers_config.hpp rename to Drivers/common/drivers_config/inc/drivers_config.hpp index 274f97e2..20d63a73 100644 --- a/Drivers/Common/Inc/drivers_config.hpp +++ b/Drivers/common/drivers_config/inc/drivers_config.hpp @@ -3,8 +3,7 @@ #include "usart.h" #include "sbus_receiver.hpp" -#include "uart_device.hpp" - +#include "dma_uart_device.hpp" /* UART Mapping */ @@ -16,5 +15,6 @@ extern SBUSReceiver* sbus_pointer; #define RFD900_UART &huart3 extern UARTDevice* pRFD900; +extern CircularBuffer *rfd900_circular_buffer; #endif \ No newline at end of file diff --git a/Drivers/common/drivers_config/src/drivers_config.cpp b/Drivers/common/drivers_config/src/drivers_config.cpp new file mode 100644 index 00000000..6f290eeb --- /dev/null +++ b/Drivers/common/drivers_config/src/drivers_config.cpp @@ -0,0 +1,19 @@ +#include "drivers_config.hpp" + +/* + creating sbusReceiver instance +*/ +SBUSReceiver sbus_instance(sbus_uart); +SBUSReceiver* sbus_pointer = &sbus_instance; + +/* + creating RFD900 instance +*/ +const uint8_t RFD900_BUF_SIZE = 280; +uint8_t rfd900_buf[RFD900_BUF_SIZE]; +CircularBuffer rfd900_circular_buffer_inst(rfd900_buf, RFD900_BUF_SIZE); + +CircularBuffer* rfd900_circular_buffer = &rfd900_circular_buffer_inst; + +UARTDevice rfd900Instance(RFD900_UART, rfd900_circular_buffer); +UARTDevice* pRFD900 = &rfd900Instance; diff --git a/Drivers/IWDG_Driver/Inc/independent_watchdog.h b/Drivers/iwdg_driver/inc/independent_watchdog.h similarity index 99% rename from Drivers/IWDG_Driver/Inc/independent_watchdog.h rename to Drivers/iwdg_driver/inc/independent_watchdog.h index c4088384..4dc8e154 100644 --- a/Drivers/IWDG_Driver/Inc/independent_watchdog.h +++ b/Drivers/iwdg_driver/inc/independent_watchdog.h @@ -15,5 +15,6 @@ class IndependentWatchdog : public Watchdog { }; + #endif /* SRC_DRIVERS_INDEPENDENTWATCHDOG_H_ */ diff --git a/Drivers/IWDG_Driver/Inc/watchdog.h b/Drivers/iwdg_driver/inc/watchdog.h similarity index 91% rename from Drivers/IWDG_Driver/Inc/watchdog.h rename to Drivers/iwdg_driver/inc/watchdog.h index 15465f05..ffd556c4 100644 --- a/Drivers/IWDG_Driver/Inc/watchdog.h +++ b/Drivers/iwdg_driver/inc/watchdog.h @@ -6,6 +6,4 @@ class Watchdog { virtual bool refreshWatchdog() = 0; }; -#endif - - +#endif \ No newline at end of file diff --git a/Drivers/IWDG_Driver/Src/independent_watchdog.cpp b/Drivers/iwdg_driver/src/independent_watchdog.cpp similarity index 99% rename from Drivers/IWDG_Driver/Src/independent_watchdog.cpp rename to Drivers/iwdg_driver/src/independent_watchdog.cpp index 0b746002..8a853c95 100644 --- a/Drivers/IWDG_Driver/Src/independent_watchdog.cpp +++ b/Drivers/iwdg_driver/src/independent_watchdog.cpp @@ -10,6 +10,7 @@ IndependentWatchdog::IndependentWatchdog(IWDG_HandleTypeDef *watchdog) { } + /** * @brief Refreshes the watchdog that is a member variable of the class * @returns true on success, false on failure diff --git a/Drivers/MotorChannel/Inc/ZP_D_MotorChannel.hpp b/Drivers/motor_channel/inc/ZP_D_MotorChannel.hpp similarity index 100% rename from Drivers/MotorChannel/Inc/ZP_D_MotorChannel.hpp rename to Drivers/motor_channel/inc/ZP_D_MotorChannel.hpp diff --git a/Drivers/MotorChannel/Inc/ZP_D_PWMChannel.hpp b/Drivers/motor_channel/inc/ZP_D_PWMChannel.hpp similarity index 100% rename from Drivers/MotorChannel/Inc/ZP_D_PWMChannel.hpp rename to Drivers/motor_channel/inc/ZP_D_PWMChannel.hpp diff --git a/Drivers/MotorChannel/Src/ZP_D_PWMChannel.cpp b/Drivers/motor_channel/src/ZP_D_PWMChannel.cpp similarity index 100% rename from Drivers/MotorChannel/Src/ZP_D_PWMChannel.cpp rename to Drivers/motor_channel/src/ZP_D_PWMChannel.cpp diff --git a/Drivers/rc_receiver/Inc/rcreceiver_datatypes.h b/Drivers/rc_receiver/inc/rcreceiver_datatypes.h similarity index 100% rename from Drivers/rc_receiver/Inc/rcreceiver_datatypes.h rename to Drivers/rc_receiver/inc/rcreceiver_datatypes.h diff --git a/Drivers/rc_receiver/Inc/sbus_defines.h b/Drivers/rc_receiver/inc/sbus_defines.h similarity index 100% rename from Drivers/rc_receiver/Inc/sbus_defines.h rename to Drivers/rc_receiver/inc/sbus_defines.h diff --git a/Drivers/rc_receiver/Inc/sbus_receiver.hpp b/Drivers/rc_receiver/inc/sbus_receiver.hpp similarity index 100% rename from Drivers/rc_receiver/Inc/sbus_receiver.hpp rename to Drivers/rc_receiver/inc/sbus_receiver.hpp diff --git a/Drivers/rc_receiver/Src/sbus_receiver.cpp b/Drivers/rc_receiver/src/sbus_receiver.cpp similarity index 100% rename from Drivers/rc_receiver/Src/sbus_receiver.cpp rename to Drivers/rc_receiver/src/sbus_receiver.cpp diff --git a/Drivers/ccontrol/Inc/ccontrol_functions.h b/Drivers/sensor_fusion/ccontrol/inc/ccontrol_functions.h similarity index 100% rename from Drivers/ccontrol/Inc/ccontrol_functions.h rename to Drivers/sensor_fusion/ccontrol/inc/ccontrol_functions.h diff --git a/Drivers/ccontrol/Src/inv.c b/Drivers/sensor_fusion/ccontrol/src/inv.c similarity index 100% rename from Drivers/ccontrol/Src/inv.c rename to Drivers/sensor_fusion/ccontrol/src/inv.c diff --git a/Drivers/ccontrol/Src/lup.c b/Drivers/sensor_fusion/ccontrol/src/lup.c similarity index 100% rename from Drivers/ccontrol/Src/lup.c rename to Drivers/sensor_fusion/ccontrol/src/lup.c diff --git a/Drivers/ccontrol/Src/mul.c b/Drivers/sensor_fusion/ccontrol/src/mul.c similarity index 100% rename from Drivers/ccontrol/Src/mul.c rename to Drivers/sensor_fusion/ccontrol/src/mul.c diff --git a/Drivers/ccontrol/Src/tran.c b/Drivers/sensor_fusion/ccontrol/src/tran.c similarity index 100% rename from Drivers/ccontrol/Src/tran.c rename to Drivers/sensor_fusion/ccontrol/src/tran.c diff --git a/Drivers/sensor_fusion/Inc/common_data_types.hpp b/Drivers/sensor_fusion/inc/common_data_types.hpp similarity index 100% rename from Drivers/sensor_fusion/Inc/common_data_types.hpp rename to Drivers/sensor_fusion/inc/common_data_types.hpp diff --git a/Drivers/sensor_fusion/Inc/manhony_ahrs.h b/Drivers/sensor_fusion/inc/manhony_ahrs.h similarity index 100% rename from Drivers/sensor_fusion/Inc/manhony_ahrs.h rename to Drivers/sensor_fusion/inc/manhony_ahrs.h diff --git a/Drivers/sensor_fusion/Inc/math_constants.hpp b/Drivers/sensor_fusion/inc/math_constants.hpp similarity index 100% rename from Drivers/sensor_fusion/Inc/math_constants.hpp rename to Drivers/sensor_fusion/inc/math_constants.hpp diff --git a/Drivers/sensor_fusion/Inc/sensor_fusion.hpp b/Drivers/sensor_fusion/inc/sensor_fusion.hpp similarity index 100% rename from Drivers/sensor_fusion/Inc/sensor_fusion.hpp rename to Drivers/sensor_fusion/inc/sensor_fusion.hpp diff --git a/Drivers/sensor_fusion/Inc/sensor_fusion_interface.hpp b/Drivers/sensor_fusion/inc/sensor_fusion_interface.hpp similarity index 100% rename from Drivers/sensor_fusion/Inc/sensor_fusion_interface.hpp rename to Drivers/sensor_fusion/inc/sensor_fusion_interface.hpp diff --git a/Drivers/sensor_fusion/Inc/sf_config.h b/Drivers/sensor_fusion/inc/sf_config.h similarity index 100% rename from Drivers/sensor_fusion/Inc/sf_config.h rename to Drivers/sensor_fusion/inc/sf_config.h diff --git a/Drivers/sensor_fusion/Src/manhony_ahrs.cpp b/Drivers/sensor_fusion/src/manhony_ahrs.cpp similarity index 100% rename from Drivers/sensor_fusion/Src/manhony_ahrs.cpp rename to Drivers/sensor_fusion/src/manhony_ahrs.cpp diff --git a/Drivers/sensor_fusion/Src/sensor_fusion.cpp b/Drivers/sensor_fusion/src/sensor_fusion.cpp similarity index 100% rename from Drivers/sensor_fusion/Src/sensor_fusion.cpp rename to Drivers/sensor_fusion/src/sensor_fusion.cpp diff --git a/Drivers/sensor_fusion/Src/sensor_fusion_interface.cpp b/Drivers/sensor_fusion/src/sensor_fusion_interface.cpp similarity index 100% rename from Drivers/sensor_fusion/Src/sensor_fusion_interface.cpp rename to Drivers/sensor_fusion/src/sensor_fusion_interface.cpp diff --git a/Drivers/Tests/CircularBufferTest.cpp b/Drivers/tests/CircularBufferTest.cpp similarity index 100% rename from Drivers/Tests/CircularBufferTest.cpp rename to Drivers/tests/CircularBufferTest.cpp diff --git a/TelemetryManager/Inc/GroundStationCommunication.hpp b/TelemetryManager/Inc/GroundStationCommunication.hpp index 0194553f..0470b2e2 100644 --- a/TelemetryManager/Inc/GroundStationCommunication.hpp +++ b/TelemetryManager/Inc/GroundStationCommunication.hpp @@ -8,11 +8,12 @@ * @date 2023-08-24 * @author Yarema Dzulynsky: initial structure * @author Roni Kant: implementation - * + * * @warning Any issues you think are important/foresee in the future? */ -#include "CircularBuffer.hpp" +#include "TMCircularBuffer.hpp" +#include "drivers_config.hpp" #ifndef GROUNDSTATIONCOMMUNICATION_H #define GROUNDSTATIONCOMMUNICATION_H @@ -26,23 +27,34 @@ class GroundStationCommunication { public: /** - * @brief Construct a new Ground Station Communication object. Do whatever needs to be done here. - * + * @brief Construct a new Ground Station Communication object. Do whatever needs to be done + * here. + * @param DMAReceiveBuffer A TMCircularBuffer created FROM the rfd900_circular_buffer in the drivers_config.hpp file. + * @param lowPriorityTransmitBuffer A uint8_t buffer to be used by a TM CircularBuffer + * @param highPriorityTransmitBuffer A uint8_t buffer to be used by a TM CircularBuffer + * @param length The length of the buffers. */ - GroundStationCommunication(); + GroundStationCommunication(TMCircularBuffer& DMAReceiveBuffer, uint8_t* lowPriorityTransmitBuffer, uint8_t* highPriorityTransmitBuffer, int length); ~GroundStationCommunication(); - /* + + /** + * To make c++ happy while using rfd900_circular_buffer from drivers_config.hpp, we need to + * create a pointer to the buffer. Then we dereference it. + */ + // TMCircularBuffer* DMAReceiveBufferPtr = new TMCircularBuffer(rfd900_circular_buffer); + +/* * When the DMA interrupt is triggered the data should be stored in the DMAReceiveBuffer * IF there is space. */ - CircularBuffer DMAReceiveBuffer; + TMCircularBuffer& DMAReceiveBuffer; // low priority/Non routine Mavlink bytes to be sent to the ground station. - CircularBuffer lowPriorityTransmitBuffer; + TMCircularBuffer lowPriorityTransmitBuffer; // high priority/Routine Mavlink bytes to be sent to the ground station. - CircularBuffer highPriorityTransmitBuffer; + TMCircularBuffer highPriorityTransmitBuffer; /** * @brief This function sends data from a CircularBuffer to the ground station. @@ -56,7 +68,7 @@ class GroundStationCommunication { * @param transmissionBuffer A CircularBuffer containing the data/MAVLink bytes to be sent * to the ground station */ - void transmit(CircularBuffer &transmissionBuffer); + void transmit(TMCircularBuffer& transmissionBuffer); /** * @brief This is the Interrupt Service Routine (ISR) for when the RFD 900 receives data from diff --git a/TelemetryManager/Inc/MavlinkTranslator.hpp b/TelemetryManager/Inc/MavlinkTranslator.hpp index 359e0bd8..8c3f3bf2 100644 --- a/TelemetryManager/Inc/MavlinkTranslator.hpp +++ b/TelemetryManager/Inc/MavlinkTranslator.hpp @@ -11,7 +11,7 @@ * @warning Any issues you think are important/foresee in the future? */ -#include "CircularBuffer.hpp" +#include "TMCircularBuffer.hpp" #include "Official_Mavlink_2_Library/common/mavlink.h" #ifndef MAVLINKTRANSLATOR_H #define MAVLINKTRANSLATOR_H @@ -38,7 +38,7 @@ class MavlinkTranslator { * @param rxFromGroundByteQueue The CircularBuffer containing the bytes received from the ground * station. waiting to be decoded. */ - void bytesToMavlinkMsg(CircularBuffer &rxFromGroundByteQueue); + void bytesToMavlinkMsg(TMCircularBuffer &rxFromGroundByteQueue); /** * @brief Converts Mavlink messages to bytes and adds them to the txToGroundByteQueue. @@ -48,7 +48,7 @@ class MavlinkTranslator { * station. */ void addMavlinkMsgToByteQueue(mavlink_message_t &msg, - CircularBuffer &txToGroundByteQueue); + TMCircularBuffer &txToGroundByteQueue); }; #endif // MAVLINKTRANSLATOR_H diff --git a/TelemetryManager/Inc/CircularBuffer.hpp b/TelemetryManager/Inc/TMCircularBuffer.hpp similarity index 65% rename from TelemetryManager/Inc/CircularBuffer.hpp rename to TelemetryManager/Inc/TMCircularBuffer.hpp index 11247644..2d72c979 100644 --- a/TelemetryManager/Inc/CircularBuffer.hpp +++ b/TelemetryManager/Inc/TMCircularBuffer.hpp @@ -1,5 +1,5 @@ /** - * @file CircularBuffer.hpp + * @file TMCircularBuffer.hpp * @brief What does this file do? * * @note Anything future maintainers should know about this file? @@ -8,14 +8,16 @@ * @date 2023-08-24 * @author Yarema Dzulynsky: initial structure * @author Rahul Ramkumar: implementation - * + * * @warning Any issues you think are important/foresee in the future? */ -#ifndef CIRCULARBUFFER_H -#define CIRCULARBUFFER_H +#ifndef TMCIRCULARBUFFER_H +#define TMCIRCULARBUFFER_H + +#include "circular_buffer.hpp" -class CircularBuffer { +class TMCircularBuffer : public CircularBuffer { using MAVLinkByte = unsigned char; // not 100% sure if this is the right type public: @@ -23,21 +25,20 @@ class CircularBuffer { * @brief Construct a new Circular Buffer object. Do whatever needs to be done here. * */ - CircularBuffer(); + TMCircularBuffer(uint8_t* buf, uint16_t size); /** - * @brief Destroy and cleanup memory (everything should be static anyways). Do whatever - * needs to be done here. + * @brief Construct a new Circular Buffer object. Do whatever needs to be done here. * */ - ~CircularBuffer(); + TMCircularBuffer(CircularBuffer* buf); /** - * @brief Provides the number of bytes available in the queue + * @brief Destroy and cleanup memory (everything should be static anyways). Do whatever + * needs to be done here. * - * @return int The number of bytes available in the queue. */ - int remainingMemory(); + ~TMCircularBuffer(); /** * @brief Dequeue a byte from the queue @@ -59,21 +60,21 @@ class CircularBuffer { * an ISR was triggered while we were in the middle of enqueuing a message, we * only send completed messages and keep the partial message to be finished after the ISR. * These partial messages once filled will be sent during the next transmission. - * + * * @return int The index of the last full message in the queue determined by the end flag - * in the MAVLink message. - * + * in the MAVLink message. + * */ int lastFullMessageEndIndex(); -/** - * @brief Returns the index of the current byte in the queue. This is useful for when we want to - * avoid sending partial messages, as we know the index of the end of the last complete message. - * Therefore, we can check if the current byte is just before the last complete message and if so, we - * can avoid sending it. - * - * @return int The index of the current byte in the queue. - */ + /** + * @brief Returns the index of the current byte in the queue. This is useful for when we want to + * avoid sending partial messages, as we know the index of the end of the last complete message. + * Therefore, we can check if the current byte is just before the last complete message and if + * so, we can avoid sending it. + * + * @return int The index of the current byte in the queue. + */ int currentIndex(); }; diff --git a/TelemetryManager/Src/CircularBuffer.cpp b/TelemetryManager/Src/CircularBuffer.cpp deleted file mode 100644 index db1db439..00000000 --- a/TelemetryManager/Src/CircularBuffer.cpp +++ /dev/null @@ -1,28 +0,0 @@ - -#include "CircularBuffer.hpp" - -CircularBuffer::CircularBuffer() { - // Constructor -} - -CircularBuffer::~CircularBuffer() { - // Destructor -} - -int CircularBuffer::remainingMemory() { return -1; } - -CircularBuffer::MAVLinkByte CircularBuffer::dequeue() { return 0; } - -void CircularBuffer::enqueue(MAVLinkByte byte) { - // Enqueue the byte -} - -int CircularBuffer::lastFullMessageEndIndex() { - /* - Rahul: This one is a bit tricky cause you need to know the structure of the MAVLink message. - I can help you with this one if you want. - */ - return -1; -} - -int CircularBuffer::currentIndex() { return -1; } diff --git a/TelemetryManager/Src/GroundStationCommunication.cpp b/TelemetryManager/Src/GroundStationCommunication.cpp index 4bbd7391..b1413f76 100644 --- a/TelemetryManager/Src/GroundStationCommunication.cpp +++ b/TelemetryManager/Src/GroundStationCommunication.cpp @@ -2,9 +2,16 @@ #include "GroundStationCommunication.hpp" +#include "drivers_config.hpp" -GroundStationCommunication::GroundStationCommunication() { - // Constructor +GroundStationCommunication::GroundStationCommunication( + TMCircularBuffer& DMAReceiveBuffer, uint8_t *lowPriorityTransmitBuffer, + uint8_t *highPriorityTransmitBuffer, int length): + DMAReceiveBuffer(DMAReceiveBuffer), + lowPriorityTransmitBuffer(lowPriorityTransmitBuffer, length), + highPriorityTransmitBuffer(highPriorityTransmitBuffer, length) { + + } GroundStationCommunication::~GroundStationCommunication() { @@ -13,7 +20,7 @@ GroundStationCommunication::~GroundStationCommunication() { // ** Implement transmit first ** -void GroundStationCommunication::transmit(CircularBuffer &transmissionBuffer) { +void GroundStationCommunication::transmit(TMCircularBuffer &transmissionBuffer) { // START: Send the bytes in transmissionBuffer to the ground station via RFD900 // END: Send the bytes in transmissionBuffer to the ground station via RFD900 @@ -22,17 +29,15 @@ void GroundStationCommunication::transmit(CircularBuffer &transmissionBuffer) { } void GroundStationCommunication::receiveInterruptServiceRoutine() { - - int bytesReceived = 0; // replace with actual number of bytes received + int bytesReceived = 0; // replace with actual number of bytes received // if GSC.DMAReceiveBuffer has enough space for the new data add it // otherwise discard the data - if(DMAReceiveBuffer.remainingMemory() > bytesReceived) { + if (DMAReceiveBuffer.remainingMemory() > bytesReceived) { // add the new data to GSC.DMAReceiveBuffer - } - else{ + } else { // discard the new data - //not a great way to handle this, but it's a start + // not a great way to handle this, but it's a start } // end of ISR diff --git a/TelemetryManager/Src/MavlinkTranslator.cpp b/TelemetryManager/Src/MavlinkTranslator.cpp index 32731403..4087f604 100644 --- a/TelemetryManager/Src/MavlinkTranslator.cpp +++ b/TelemetryManager/Src/MavlinkTranslator.cpp @@ -10,13 +10,13 @@ MavlinkTranslator::~MavlinkTranslator() // Destructor } -void MavlinkTranslator::bytesToMavlinkMsg(CircularBuffer &rxFromGroundByteQueue) +void MavlinkTranslator::bytesToMavlinkMsg(TMCircularBuffer &rxFromGroundByteQueue) { // Take bytes in rxFromGroundByteQueue and convert them to Mavlink messages } -void MavlinkTranslator::addMavlinkMsgToByteQueue(mavlink_message_t &msg, CircularBuffer &txToGroundByteQueue) +void MavlinkTranslator::addMavlinkMsgToByteQueue(mavlink_message_t &msg, TMCircularBuffer &txToGroundByteQueue) { // Take Mavlink messages in txToGroundByteQueue and convert them to bytes diff --git a/TelemetryManager/Src/TMCircularBuffer.cpp b/TelemetryManager/Src/TMCircularBuffer.cpp new file mode 100644 index 00000000..91b1928f --- /dev/null +++ b/TelemetryManager/Src/TMCircularBuffer.cpp @@ -0,0 +1,30 @@ + +#include "CircularBuffer.hpp" + +TMCircularBuffer::TMCircularBuffer(uint8_t* buf, uint16_t size): CircularBuffer(buf, size) { + // Constructor +} + +TMCircularBuffer::TMCircularBuffer(CircularBuffer buf): CircularBuffer(buf) { + // Constructor +} + +TMCircularBuffer::~TMCircularBuffer() { + // Destructor +} + +TMCircularBuffer::MAVLinkByte TMCircularBuffer::dequeue() { return 0; } + +void TMCircularBuffer::enqueue(MAVLinkByte byte) { + // Enqueue the byte +} + +int TMCircularBuffer::lastFullMessageEndIndex() { + /* + Rahul: This one is a bit tricky cause you need to know the structure of the MAVLink message. + I can help you with this one if you want. + */ + return -1; +} + +int TMCircularBuffer::currentIndex() { return -1; } diff --git a/Tools/Firmware/CMakeLists.txt b/Tools/Firmware/CMakeLists.txt index 2102c3a6..5b685999 100644 --- a/Tools/Firmware/CMakeLists.txt +++ b/Tools/Firmware/CMakeLists.txt @@ -24,16 +24,15 @@ include_directories( ${ROOT_DIR}/TelemetryManager/Inc ## Driver Includes ## - ${ROOT_DIR}/Drivers/rc_receiver/Inc - ${ROOT_DIR}/Drivers/Common/Inc - - ${ROOT_DIR}/Drivers/ccontrol/Inc - ${ROOT_DIR}/Drivers/sensor_fusion/Inc - ${ROOT_DIR}/Drivers/IWDG_Driver/Inc - ${ROOT_DIR}/Drivers/MotorChannel/Inc - - ${ROOT_DIR}/Drivers/UARTDevice/Inc - ${ROOT_DIR}/Drivers/Common/Inc + + ${ROOT_DIR}/Drivers/common/circular_buffer/inc + ${ROOT_DIR}/Drivers/common/drivers_config/inc + ${ROOT_DIR}/Drivers/common/dma_uart_device/inc + ${ROOT_DIR}/Drivers/iwdg_driver/inc + ${ROOT_DIR}/Drivers/motor_channel/inc + ${ROOT_DIR}/Drivers/rc_receiver/inc + ${ROOT_DIR}/Drivers/sensor_fusion/inc + ${ROOT_DIR}/Drivers/sensor_fusion/ccontrol/inc ## Boardfiles Includes ## ${ROOT_DIR}/Boardfiles/${FOLDER_NAME}/Drivers/${FAMILY_NAME}_HAL_Driver/Inc @@ -78,23 +77,23 @@ set(SYSTEM_MANAGER_C_SOURCES "${SYSTEM_MANAGER}/Src/*.c") set(SYSTEM_MANAGER_CXX_SOURCES "${SYSTEM_MANAGER}/Src/*.cpp") set(DRIVERS_DIR ${ROOT_DIR}/Drivers) -set(DRIVERS_C_SOURCES "${DRIVERS_DIR}/ccontrol/Src/*.c") +set(DRIVERS_C_SOURCES "${DRIVERS_DIR}/sensor_fusion/ccontrol/Src/*.c") set(DRIVERS_CXX_SOURCES "${DRIVERS_DIR}/sensor_fusion/Src/*.cpp") ## Drivers Sources ## -set(DRIVERS_RcReceiver_DIR ${ROOT_DIR}/Drivers/rc_receiver/Src) +set(DRIVERS_RcReceiver_DIR ${ROOT_DIR}/Drivers/rc_receiver/src) set(DRIVERS_RcReceiver_CXX_SOURCES "${DRIVERS_RcReceiver_DIR}/*.cpp") -set(DRIVERS_Common_DIR ${ROOT_DIR}/Drivers/Common/Src) -set(DRIVERS_MotorChannel_DIR ${ROOT_DIR}/Drivers/MotorChannel/Src) +set(DRIVERS_Common_DIR ${ROOT_DIR}/Drivers/common) +set(DRIVERS_MotorChannel_DIR ${ROOT_DIR}/Drivers/motor_channel/src) set(DRIVERS_MotorChannel_CXX_SOURCES "${DRIVERS_MotorChannel_DIR}/*.cpp") set(DRIVERS_Common_CXX_SOURCES "${DRIVERS_Common_DIR}/*.cpp") -set(DRIVERS_IWDGDriver_DIR ${ROOT_DIR}/Drivers/IWDG_Driver/Src) +set(DRIVERS_IWDGDriver_DIR ${ROOT_DIR}/Drivers/iwdg_driver/src) set(DRIVERS_IWDGDriver_CXX_SOURCES "${DRIVERS_IWDGDriver_DIR}/*.cpp") ## Actually find the sources, NOTE: if you add a new source above, add it here! ## ## Drivers Sources ## -set(DRIVERS_UARTDevice_DIR ${ROOT_DIR}/Drivers/UARTDevice/Src) +set(DRIVERS_UARTDevice_DIR ${ROOT_DIR}/Drivers/common/dma_uart_device/src) set(DRIVERS_UARTDevice_CXX_SOURCES "${DRIVERS_UARTDevice_DIR}/*.cpp") file(GLOB_RECURSE C_SOURCES ${HAL_DRIVERS_C_SOURCES} @@ -121,6 +120,13 @@ message("C++ Sources: ${CXX_SOURCES}") set(STARTUP_ASM_FILE ${ROOT_DIR}/Boardfiles/${STARTUP_ASM}) set(LINKER_SCRIPT_FILE ${ROOT_DIR}/Boardfiles/${LINKER_SCRIPT}) +# If warnings are so overwhelming you can't locate the actual errors, uncomment the following line +# add_compile_options( +# "$<$:-w>" # for GCC +# "$<$:-w>" # for Clang +# "$<$:/W0>" # for MSVC +# ) + add_executable(${ELF_NAME} ${C_SOURCES} ${CXX_SOURCES} ${STARTUP_ASM_FILE}) # Specify C standard we use diff --git a/Tools/Testing/CMakeLists.txt b/Tools/Testing/CMakeLists.txt index ad512dac..acb70235 100644 --- a/Tools/Testing/CMakeLists.txt +++ b/Tools/Testing/CMakeLists.txt @@ -81,24 +81,27 @@ file(GLOB TM_CODE # Drivers set(DRIVERS_FOLDER "${ROOT_DIR}/Drivers") -set(DRIVERS_INC "${DRIVERS_FOLDER}/Common/Inc") -set(DRIVERS_SRC "{$DRIVERS_FOLDER}/Src") -set(MOTORCHANNEL_INC "${DRIVERS_FOLDER}/MotorChannel/Inc") -set(MOTORCHANNEL_SRC "${DRIVERS_FOLDER}/MotorChannel/Src") -# Driver Mocks + +set(MOTORCHANNEL_INC "${DRIVERS_FOLDER}/motor_channel/inc") +set(MOTORCHANNEL_SRC "${DRIVERS_FOLDER}/motor_channel/src") + +set(CIRCULAR_BUFFER_INC "${DRIVERS_FOLDER}/common/circular_buffer/inc") +set(CIRCULAR_BUFFER_SRC "${DRIVERS_FOLDER}/common/circular_buffer/src") + +set(DRIVERS_CONFIG_INC "${DRIVERS_FOLDER}/Drivers/common/drivers_config/inc") + set(MOTORCHANNEL_MOCK_INC "${ROOT_DIR}/Testing/Mocks/Inc") set(MOTORCHANNEL_MOCK_SRC "${ROOT_DIR}/Testing/Mocks/Src") -include_directories(${DRIVERS_INC} ${MOTORCHANNEL_INC} ${MOTORCHANNEL_MOCK_INC}) +include_directories(${DRIVERS_CONFIG_INC} ${CIRCULAR_BUFFER_INC} ${MOTORCHANNEL_INC} ${MOTORCHANNEL_MOCK_INC}) file(GLOB DRIVERS_CODE "${DRIVERS_FOLDER}/Tests/*.cpp" # add necessary Drivers source files below # "${DRIVERS_SRC}/foo.cpp" - "${DRIVERS_FOLDER}/Common/Src/circular_buffer.cpp" + "${DRIVERS_FOLDER}/common/circular_buffer/src/circular_buffer.cpp" "${MOTORCHANNEL_MOCK_SRC}/*.cpp" ) - # Common set(COMMON_FOLDER "${ROOT_DIR}/Common") set(COMMON_INC "${COMMON_FOLDER}/Inc") @@ -129,6 +132,13 @@ include_directories(${ROOT_DIR}/Config_Models) file(GLOB MODELS_CODE ) +# If warnings are so overwhelming you can't locate the actual errors, uncomment the following line +# add_compile_options( +# "$<$:-w>" # for GCC +# "$<$:-w>" # for Clang +# "$<$:/W0>" # for MSVC +# ) + # --- ZeroPilot File Indexing End --- add_executable(${PROJECT_NAME} From 49dab67266ebc9aeab3ca7cb4e93699c1b9fe067 Mon Sep 17 00:00:00 2001 From: Ayush Ganguly <69713915+AYUSH325@users.noreply.github.com> Date: Wed, 29 May 2024 12:04:52 -0400 Subject: [PATCH 06/15] TM Add Unit Tests Part1 (#54) Co-authored-by: Ayush Ganguly --- .../Mocks/Inc/MockGroundStationCommunication.hpp | 13 +++++++++++++ .../Tests/Mocks/Inc/MockMavlinkTranslator.hpp | 10 ++++++++++ .../Tests/Mocks/Inc/MockTMCircularBuffer.hpp | 12 ++++++++++++ .../Tests/Mocks/Inc/MockTelemetryManager.hpp | 9 +++++++++ 4 files changed, 44 insertions(+) create mode 100644 TelemetryManager/Tests/Mocks/Inc/MockGroundStationCommunication.hpp create mode 100644 TelemetryManager/Tests/Mocks/Inc/MockMavlinkTranslator.hpp create mode 100644 TelemetryManager/Tests/Mocks/Inc/MockTMCircularBuffer.hpp create mode 100644 TelemetryManager/Tests/Mocks/Inc/MockTelemetryManager.hpp diff --git a/TelemetryManager/Tests/Mocks/Inc/MockGroundStationCommunication.hpp b/TelemetryManager/Tests/Mocks/Inc/MockGroundStationCommunication.hpp new file mode 100644 index 00000000..0c594a6c --- /dev/null +++ b/TelemetryManager/Tests/Mocks/Inc/MockGroundStationCommunication.hpp @@ -0,0 +1,13 @@ +#include +#include "GroundStationCommunication.hpp" +#include "TMCircularBuffer.hpp" + +class MockGroundStationCommunication : public GroundStationCommunication +{ + public: + + MOCK_METHOD(void, transmit, (TMCircularBuffer buffer)); + MOCK_METHOD(void, receiveInterruptServiceRoutine, ()); + +}; + diff --git a/TelemetryManager/Tests/Mocks/Inc/MockMavlinkTranslator.hpp b/TelemetryManager/Tests/Mocks/Inc/MockMavlinkTranslator.hpp new file mode 100644 index 00000000..212cc2bc --- /dev/null +++ b/TelemetryManager/Tests/Mocks/Inc/MockMavlinkTranslator.hpp @@ -0,0 +1,10 @@ +#include "gmock/gmock.h" +#include "MavlinkTranslator.hpp" +#include "TMCircularBuffer.hpp" +#include "Official_Mavlink_2_Library/common/mavlink.h" + +class MockMavlinkTranslator : public MavlinkTranslator +{ + MOCK_METHOD(void, bytesToMavlinkMsg, (TMCircularBuffer buffer)); + MOCK_METHOD(void, addMavlinkMsgToByteQueue, (mavlink_message_t msg, TMCircularBuffer buffer)); +}; diff --git a/TelemetryManager/Tests/Mocks/Inc/MockTMCircularBuffer.hpp b/TelemetryManager/Tests/Mocks/Inc/MockTMCircularBuffer.hpp new file mode 100644 index 00000000..62df0b9a --- /dev/null +++ b/TelemetryManager/Tests/Mocks/Inc/MockTMCircularBuffer.hpp @@ -0,0 +1,12 @@ +#include +#include "TMCircularBuffer.hpp" + +class MockTMCircularBuffer : public TMCircularBuffer +{ + public: + + MOCK_METHOD(unsigned char, dequeue, ()); + MOCK_METHOD(void, enqueue, (unsigned char)); + MOCK_METHOD(int, lastFullMessageEndIndex, ()); + MOCK_METHOD(int, current_index, ()); +}; diff --git a/TelemetryManager/Tests/Mocks/Inc/MockTelemetryManager.hpp b/TelemetryManager/Tests/Mocks/Inc/MockTelemetryManager.hpp new file mode 100644 index 00000000..85b36010 --- /dev/null +++ b/TelemetryManager/Tests/Mocks/Inc/MockTelemetryManager.hpp @@ -0,0 +1,9 @@ +#include +#include "TelemetryManager.hpp" + +class MockTelemetryManager : public TelemetryManager +{ + public: + MOCK_METHOD(void, init, ()); + MOCK_METHOD(void, update, ()); +}; From e7f1d4dc76b2cf04d97ff094783287dda12198d5 Mon Sep 17 00:00:00 2001 From: Le Kang Wang <70457170+lekangwang@users.noreply.github.com> Date: Wed, 12 Jun 2024 20:12:35 -0400 Subject: [PATCH 07/15] SDMMC SD Card Drivers (#45) --- Boardfiles/nucleol552zeq/.cproject | 18 +- Boardfiles/nucleol552zeq/.mxproject | 75 +- .../.settings/language.settings.xml | 8 +- .../.settings/stm32cubeide.project.prefs | 2 +- .../nucleol552zeq/Core/Inc/FreeRTOSConfig.h | 3 + Boardfiles/nucleol552zeq/Core/Inc/sdmmc.h | 52 + .../Core/Inc/stm32l5xx_hal_conf.h | 2 +- .../nucleol552zeq/Core/Inc/stm32l5xx_it.h | 4 +- Boardfiles/nucleol552zeq/Core/Inc/usart.h | 3 - Boardfiles/nucleol552zeq/Core/Src/main.cpp | 17 +- Boardfiles/nucleol552zeq/Core/Src/sdmmc.c | 144 + .../nucleol552zeq/Core/Src/stm32l5xx_it.c | 35 +- Boardfiles/nucleol552zeq/Core/Src/usart.c | 133 - .../Inc/stm32l5xx_hal_sd.h | 800 +++ .../Inc/stm32l5xx_hal_sd_ex.h | 110 + .../Inc/stm32l5xx_ll_sdmmc.h | 1113 +++ .../Src/stm32l5xx_hal_sd.c | 4047 +++++++++++ .../Src/stm32l5xx_hal_sd_ex.c | 313 + .../Src/stm32l5xx_ll_sdmmc.c | 1644 +++++ .../nucleol552zeq/FATFS/App/app_fatfs.c | 113 + .../nucleol552zeq/FATFS/App/app_fatfs.h | 68 + .../nucleol552zeq/FATFS/Target/ffconf.h | 269 + .../Third_Party/FatFs/src/diskio.c | 141 + .../Third_Party/FatFs/src/diskio.h | 80 + .../Middlewares/Third_Party/FatFs/src/ff.c | 6140 +++++++++++++++++ .../Middlewares/Third_Party/FatFs/src/ff.h | 361 + .../Third_Party/FatFs/src/ff_gen_drv.c | 122 + .../Third_Party/FatFs/src/ff_gen_drv.h | 80 + .../Third_Party/FatFs/src/integer.h | 38 + .../Third_Party/FatFs/src/option/syscall.c | 177 + .../nucleol552zeq/STM32L552ZETXQ_FLASH.ld | 4 +- Boardfiles/nucleol552zeq/nucleol552zeq.ioc | 151 +- Drivers/sd_card/inc/bsp_driver_sd.h | 64 + Drivers/sd_card/inc/log_util.h | 13 + Drivers/sd_card/inc/sd_diskio.h | 40 + Drivers/sd_card/src/bsp_driver_sd.c | 173 + Drivers/sd_card/src/log_util.c | 98 + Drivers/sd_card/src/sd_diskio.c | 319 + Tools/Firmware/CMakeLists.txt | 21 +- 39 files changed, 16733 insertions(+), 262 deletions(-) create mode 100644 Boardfiles/nucleol552zeq/Core/Inc/sdmmc.h create mode 100644 Boardfiles/nucleol552zeq/Core/Src/sdmmc.c create mode 100644 Boardfiles/nucleol552zeq/Drivers/STM32L5xx_HAL_Driver/Inc/stm32l5xx_hal_sd.h create mode 100644 Boardfiles/nucleol552zeq/Drivers/STM32L5xx_HAL_Driver/Inc/stm32l5xx_hal_sd_ex.h create mode 100644 Boardfiles/nucleol552zeq/Drivers/STM32L5xx_HAL_Driver/Inc/stm32l5xx_ll_sdmmc.h create mode 100644 Boardfiles/nucleol552zeq/Drivers/STM32L5xx_HAL_Driver/Src/stm32l5xx_hal_sd.c create mode 100644 Boardfiles/nucleol552zeq/Drivers/STM32L5xx_HAL_Driver/Src/stm32l5xx_hal_sd_ex.c create mode 100644 Boardfiles/nucleol552zeq/Drivers/STM32L5xx_HAL_Driver/Src/stm32l5xx_ll_sdmmc.c create mode 100644 Boardfiles/nucleol552zeq/FATFS/App/app_fatfs.c create mode 100644 Boardfiles/nucleol552zeq/FATFS/App/app_fatfs.h create mode 100644 Boardfiles/nucleol552zeq/FATFS/Target/ffconf.h create mode 100644 Boardfiles/nucleol552zeq/Middlewares/Third_Party/FatFs/src/diskio.c create mode 100644 Boardfiles/nucleol552zeq/Middlewares/Third_Party/FatFs/src/diskio.h create mode 100644 Boardfiles/nucleol552zeq/Middlewares/Third_Party/FatFs/src/ff.c create mode 100644 Boardfiles/nucleol552zeq/Middlewares/Third_Party/FatFs/src/ff.h create mode 100644 Boardfiles/nucleol552zeq/Middlewares/Third_Party/FatFs/src/ff_gen_drv.c create mode 100644 Boardfiles/nucleol552zeq/Middlewares/Third_Party/FatFs/src/ff_gen_drv.h create mode 100644 Boardfiles/nucleol552zeq/Middlewares/Third_Party/FatFs/src/integer.h create mode 100644 Boardfiles/nucleol552zeq/Middlewares/Third_Party/FatFs/src/option/syscall.c create mode 100644 Drivers/sd_card/inc/bsp_driver_sd.h create mode 100644 Drivers/sd_card/inc/log_util.h create mode 100644 Drivers/sd_card/inc/sd_diskio.h create mode 100644 Drivers/sd_card/src/bsp_driver_sd.c create mode 100644 Drivers/sd_card/src/log_util.c create mode 100644 Drivers/sd_card/src/sd_diskio.c diff --git a/Boardfiles/nucleol552zeq/.cproject b/Boardfiles/nucleol552zeq/.cproject index bddcc6dd..20678b12 100644 --- a/Boardfiles/nucleol552zeq/.cproject +++ b/Boardfiles/nucleol552zeq/.cproject @@ -23,7 +23,7 @@ @@ -67,6 +70,9 @@ + + +